diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index b283c95c28a9b..e60173068f028 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -1,10 +1,9 @@ ### Automatically generated from package.xml ### common/autoware_ad_api_specs/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp common/autoware_auto_common/** opensource@apex.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp -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 @@ -21,7 +20,6 @@ common/goal_distance_calculator/** taiki.tanaka@tier4.jp common/grid_map_utils/** maxime.clement@tier4.jp common/interpolation/** fumiya.watanabe@tier4.jp takayuki.murooka@tier4.jp common/kalman_filter/** koji.minoda@tier4.jp takeshi.ishita@tier4.jp yukihiro.saito@tier4.jp -common/mission_planner_rviz_plugin/** isamu.takagi@tier4.jp common/motion_utils/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp common/object_recognition_utils/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp takayuki.murooka@tier4.jp yoshi.ri@tier4.jp common/osqp_interface/** fumiya.watanabe@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp @@ -29,34 +27,25 @@ common/path_distance_calculator/** isamu.takagi@tier4.jp common/perception_utils/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp yoshi.ri@tier4.jp common/polar_grid/** yukihiro.saito@tier4.jp common/qp_interface/** fumiya.watanabe@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp -common/rtc_manager_rviz_plugin/** taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp common/signal_processing/** ali.boyali@tier4.jp fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp common/tensorrt_common/** dan.umeda@tier4.jp manato.hirabayashi@tier4.jp common/tier4_adapi_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp common/tier4_api_utils/** isamu.takagi@tier4.jp -common/tier4_automatic_goal_rviz_plugin/** dawid.moszynski@robotec.ai kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp common/tier4_autoware_utils/** mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp -common/tier4_calibration_rviz_plugin/** tomoya.kimura@tier4.jp common/tier4_camera_view_rviz_plugin/** makoto.ybauta@tier4.jp uken.ryu@tier4.jp -common/tier4_control_rviz_plugin/** taiki.tanaka@tier4.jp common/tier4_datetime_rviz_plugin/** isamu.takagi@tier4.jp -common/tier4_debug_rviz_plugin/** takayuki.murooka@tier4.jp common/tier4_localization_rviz_plugin/** isamu.takagi@tier4.jp takamasa.horibe@tier4.jp -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_simulated_clock_rviz_plugin/** maxime.clement@tier4.jp -common/tier4_state_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp +common/tier4_state_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp khalil@leodrive.ai common/tier4_system_rviz_plugin/** koji.minoda@tier4.jp -common/tier4_target_object_type_rviz_plugin/** takamasa.horibe@tier4.jp common/tier4_traffic_light_rviz_plugin/** satoshi.ota@tier4.jp common/tier4_vehicle_rviz_plugin/** yukihiro.saito@tier4.jp common/time_utils/** christopherj.ho@gmail.com shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/traffic_light_recognition_marker_publisher/** shumpei.wakabayashi@tier4.jp takeshi.miura@tier4.jp tomoya.kimura@tier4.jp common/traffic_light_utils/** kotaro.uetake@tier4.jp satoshi.ota@tier4.jp shunsuke.miura@tier4.jp common/tvm_utility/** ambroise.vincent@arm.com xinyu.wang@tier4.jp -control/autonomous_emergency_braking/** mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp +control/autonomous_emergency_braking/** daniel.sanchez@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp control/control_performance_analysis/** berkay@leodrive.ai 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 control/control_validator/** kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/external_cmd_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 @@ -69,15 +58,16 @@ control/pid_longitudinal_controller/** mamoru.sobue@tier4.jp takamasa.horibe@tie control/predicted_path_checker/** berkay@leodrive.ai control/pure_pursuit/** takamasa.horibe@tier4.jp control/shift_decider/** takamasa.horibe@tier4.jp +control/smart_mpc_trajectory_follower/** masayuki.aino@proxima-ai-tech.com 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 +78,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 +113,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 +132,31 @@ 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_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/autoware_behavior_velocity_planner/** kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp +planning/autoware_planning_test_manager/** kyoichi.sugahara@tier4.jp takamasa.horibe@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 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 @@ -173,13 +169,12 @@ planning/behavior_velocity_no_drivable_lane_module/** ahmed.ebrahim@leodrive.ai planning/behavior_velocity_no_stopping_area_module/** kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_occlusion_spot_module/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_out_of_lane_module/** maxime.clement@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp -planning/behavior_velocity_planner/** kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_planner_common/** fumiya.watanabe@tier4.jp isamu.takagi@tier4.jp mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_run_out_module/** kosuke.takeuchi@tier4.jp makoto.kurihara@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_speed_bump_module/** mdogru@leodrive.ai shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_stop_line_module/** fumiya.watanabe@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp zhe.shen@tier4.jp planning/behavior_velocity_template_module/** daniel.sanchez@tier4.jp -planning/behavior_velocity_traffic_light_module/** satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_velocity_traffic_light_module/** mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_virtual_traffic_light_module/** kosuke.takeuchi@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_walkway_module/** satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp planning/costmap_generator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp @@ -194,10 +189,10 @@ planning/obstacle_cruise_planner/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.j planning/obstacle_stop_planner/** berkay@leodrive.ai bnk@leodrive.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp planning/obstacle_velocity_limiter/** maxime.clement@tier4.jp 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_test_utils/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp zulfaqar.azmi@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 @@ -205,14 +200,13 @@ 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 +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,7 +215,8 @@ 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/simple_planning_simulator/** takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp +simulator/learning_based_vehicle_model/** maxime.clement@tier4.jp nagy.tomas@tier4.jp +simulator/simple_planning_simulator/** mamoru.sobue@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp temkei.kem@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@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 @@ -231,6 +226,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,10 +235,12 @@ 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 system/velodyne_monitor/** fumihito.ito@tier4.jp +tools/reaction_analyzer/** berkay@leodrive.ai vehicle/accel_brake_map_calibrator/** taiki.tanaka@tier4.jp takeshi.miura@tier4.jp tomoya.kimura@tier4.jp vehicle/external_cmd_converter/** takamasa.horibe@tier4.jp vehicle/raw_vehicle_cmd_converter/** makoto.kurihara@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp diff --git a/.github/PULL_REQUEST_TEMPLATE/small-change.md b/.github/PULL_REQUEST_TEMPLATE/small-change.md index 2ff933c43a349..e15fdd992d114 100644 --- a/.github/PULL_REQUEST_TEMPLATE/small-change.md +++ b/.github/PULL_REQUEST_TEMPLATE/small-change.md @@ -15,6 +15,10 @@ Not applicable. Not applicable. +## Interface changes + + + ## Pre-review checklist for the PR author The PR author **must** check the checkboxes below when creating the PR. diff --git a/.github/PULL_REQUEST_TEMPLATE/standard-change.md b/.github/PULL_REQUEST_TEMPLATE/standard-change.md index 7aedefd0a7bf1..391af629751e0 100644 --- a/.github/PULL_REQUEST_TEMPLATE/standard-change.md +++ b/.github/PULL_REQUEST_TEMPLATE/standard-change.md @@ -18,6 +18,19 @@ +### ROS Topic Changes + + + + + + +### ROS Parameter Changes + + + + + ## Effects on system behavior diff --git a/.github/workflows/build-and-test-arm64.yaml b/.github/workflows/build-and-test-arm64.yaml index a5e00496cc50a..c9a4b46874e18 100644 --- a/.github/workflows/build-and-test-arm64.yaml +++ b/.github/workflows/build-and-test-arm64.yaml @@ -19,7 +19,7 @@ jobs: - -cuda include: - rosdistro: humble - container: ghcr.io/autowarefoundation/autoware-openadk:latest-prebuilt + container: ghcr.io/autowarefoundation/autoware:latest-prebuilt build-depends-repos: build_depends.repos steps: - name: Check out repository diff --git a/.github/workflows/build-and-test-differential-arm64.yaml b/.github/workflows/build-and-test-differential-arm64.yaml index bd422af46bc4d..d6e49eaabc5bd 100644 --- a/.github/workflows/build-and-test-differential-arm64.yaml +++ b/.github/workflows/build-and-test-differential-arm64.yaml @@ -29,7 +29,7 @@ jobs: - -cuda include: - rosdistro: humble - container: ghcr.io/autowarefoundation/autoware-openadk:latest-prebuilt + container: ghcr.io/autowarefoundation/autoware:latest-prebuilt build-depends-repos: build_depends.repos steps: - name: Check out repository diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 3ad7b6d434f33..fb98d321fde88 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -28,7 +28,7 @@ jobs: - -cuda include: - rosdistro: humble - container: ghcr.io/autowarefoundation/autoware-openadk:latest-prebuilt + container: ghcr.io/autowarefoundation/autoware:latest-prebuilt build-depends-repos: build_depends.repos steps: - name: Check out repository @@ -77,7 +77,7 @@ jobs: clang-tidy-differential: runs-on: ubuntu-latest - container: ghcr.io/autowarefoundation/autoware-openadk:latest-prebuilt-cuda + container: ghcr.io/autowarefoundation/autoware:latest-prebuilt-cuda steps: - name: Check out repository uses: actions/checkout@v4 diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index 520c2cb9983b0..a469e7a33d190 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -21,7 +21,7 @@ jobs: - -cuda include: - rosdistro: humble - container: ghcr.io/autowarefoundation/autoware-openadk:latest-prebuilt + container: ghcr.io/autowarefoundation/autoware:latest-prebuilt build-depends-repos: build_depends.repos steps: - name: Check out repository diff --git a/build_depends.repos b/build_depends.repos index f7b3f12484015..32854cc34e362 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -41,3 +41,7 @@ repositories: type: git url: https://github.com/MORAI-Autonomous/MORAI-ROS2_morai_msgs.git version: main + universe/external/glog: # TODO: to use isGoogleInitialized() API in v0.6.0. Remove when the rosdep glog version is updated to v0.6.0 (already updated in Ubuntu 24.04) + type: git + url: https://github.com/tier4/glog.git + version: v0.6.0_t4-ros diff --git a/common/.pages b/common/.pages new file mode 100644 index 0000000000000..5ce88e0561c34 --- /dev/null +++ b/common/.pages @@ -0,0 +1,58 @@ +nav: + - 'Introduction': common + - 'Testing Libraries': + - 'autoware_testing': common/autoware_testing/design/autoware_testing-design + - 'fake_test_node': common/fake_test_node/design/fake_test_node-design + - 'Common Libraries': + - 'autoware_auto_common': + - 'comparisons': common/autoware_auto_common/design/comparisons + - 'autoware_auto_tf2': common/autoware_auto_tf2/design/autoware-auto-tf2-design + - 'autoware_point_types': common/autoware_point_types + - 'Cuda Utils': common/cuda_utils + - 'Geography Utils': common/geography_utils + - 'Global Parameter Loader': common/global_parameter_loader/Readme + - 'Glog Component': common/glog_component + - 'grid_map_utils': common/grid_map_utils + - 'interpolation': common/interpolation + - 'Kalman Filter': common/kalman_filter + - 'Motion Utils': common/motion_utils + - 'Vehicle Utils': common/motion_utils/docs/vehicle/vehicle + - 'Object Recognition Utils': common/object_recognition_utils + - 'OSQP Interface': common/osqp_interface/design/osqp_interface-design + - 'Perception Utils': common/perception_utils + - 'QP Interface': common/qp_interface/design/qp_interface-design + - 'Signal Processing': + - 'Introduction': common/signal_processing + - 'Butterworth Filter': common/signal_processing/documentation/ButterworthFilter + - 'TensorRT Common': common/tensorrt_common + - 'tier4_autoware_utils': common/tier4_autoware_utils + - 'traffic_light_utils': common/traffic_light_utils + - 'TVM Utility': + - 'Introduction': common/tvm_utility + - 'YOLOv2 Tiny Example': common/tvm_utility/tvm-utility-yolo-v2-tiny-tests + - 'RVIZ2 Plugins': + - 'autoware_auto_perception_rviz_plugin': common/autoware_auto_perception_rviz_plugin + - 'autoware_overlay_rviz_plugin': common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin + - 'autoware_mission_details_overlay_rviz_plugin': common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin + - 'bag_time_manager_rviz_plugin': common/bag_time_manager_rviz_plugin + - 'polar_grid': common/polar_grid/Readme + - 'tier4_adapi_rviz_plugin': common/tier4_adapi_rviz_plugin + - 'tier4_api_utils': common/tier4_api_utils + - 'tier4_camera_view_rviz_plugin': common/tier4_camera_view_rviz_plugin + - 'tier4_datetime_rviz_plugin': common/tier4_datetime_rviz_plugin + - 'tier4_localization_rviz_plugin': common/tier4_localization_rviz_plugin + - 'tier4_perception_rviz_plugin': common/tier4_perception_rviz_plugin + - 'tier4_planning_rviz_plugin': common/tier4_planning_rviz_plugin + - 'tier4_state_rviz_plugin': common/tier4_state_rviz_plugin + - 'tier4_system_rviz_plugin': common/tier4_system_rviz_plugin + - 'tier4_traffic_light_rviz_plugin': common/tier4_traffic_light_rviz_plugin + - 'tier4_vehicle_rviz_plugin': common/tier4_vehicle_rviz_plugin + - 'traffic_light_recognition_marker_publisher': common/traffic_light_recognition_marker_publisher/Readme + - 'Node': + - 'Goal Distance Calculator': common/goal_distance_calculator/Readme + - 'Path Distance Calculator': common/path_distance_calculator/Readme + - 'Others': + - 'autoware_ad_api_specs': common/autoware_ad_api_specs + - 'component_interface_specs': common/component_interface_specs + - 'component_interface_tools': common/component_interface_tools + - 'component_interface_utils': common/component_interface_utils diff --git a/common/README.md b/common/README.md new file mode 100644 index 0000000000000..95b8973a66b2b --- /dev/null +++ b/common/README.md @@ -0,0 +1,16 @@ +# Common + +## Getting Started + +The Autoware.Universe Common folder consists of common and testing libraries that are used by other Autoware components, as well as useful plugins for visualization in RVIZ2. + +!!! note + + In addition to the ones listed in this folder, users can also have a look at some of the add-ons in the `autoware_tools/common` documentation [page](https://autowarefoundation.github.io/autoware_tools/main/common/mission_planner_rviz_plugin/). + +## Highlights + +Some of the commonly used libraries are: + +1. `tier4_autoware_utils` +2. `motion_utils` diff --git a/common/autoware_ad_api_specs/include/autoware_ad_api_specs/system.hpp b/common/autoware_ad_api_specs/include/autoware_ad_api_specs/system.hpp new file mode 100644 index 0000000000000..09144c1d8ff50 --- /dev/null +++ b/common/autoware_ad_api_specs/include/autoware_ad_api_specs/system.hpp @@ -0,0 +1,36 @@ +// 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 AUTOWARE_AD_API_SPECS__SYSTEM_HPP_ +#define AUTOWARE_AD_API_SPECS__SYSTEM_HPP_ + +#include + +#include + +namespace autoware_ad_api::system +{ + +struct Heartbeat +{ + using Message = autoware_adapi_v1_msgs::msg::Heartbeat; + static constexpr char name[] = "/api/system/heartbeat"; + static constexpr size_t depth = 10; + static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT; + static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE; +}; + +} // namespace autoware_ad_api::system + +#endif // AUTOWARE_AD_API_SPECS__SYSTEM_HPP_ diff --git a/common/autoware_auto_common/include/autoware_auto_common/common/types.hpp b/common/autoware_auto_common/include/autoware_auto_common/common/types.hpp index 1c7dfe48c7ec8..83b8287ff60d4 100644 --- a/common/autoware_auto_common/include/autoware_auto_common/common/types.hpp +++ b/common/autoware_auto_common/include/autoware_auto_common/common/types.hpp @@ -37,7 +37,9 @@ namespace types // We don't currently require code to comply to MISRA, but we should try to where it is // easily possible. using bool8_t = bool; +#if __cplusplus < 201811L || !__cpp_char8_t using char8_t = char; +#endif using uchar8_t = unsigned char; // If we ever compile on a platform where this is not true, float32_t and float64_t definitions // need to be adjusted. diff --git a/common/autoware_auto_common/include/autoware_auto_common/helper_functions/message_adapters.hpp b/common/autoware_auto_common/include/autoware_auto_common/helper_functions/message_adapters.hpp index d3bda57b3374f..cc2fb0e41c372 100644 --- a/common/autoware_auto_common/include/autoware_auto_common/helper_functions/message_adapters.hpp +++ b/common/autoware_auto_common/include/autoware_auto_common/helper_functions/message_adapters.hpp @@ -36,7 +36,7 @@ using TimeStamp = builtin_interfaces::msg::Time; /// \brief Helper class to check existence of header file in compile time: /// https://stackoverflow.com/a/16000226/2325407 -template +template struct HasHeader : std::false_type { }; @@ -48,60 +48,60 @@ struct HasHeader : std::true_type /////////// Template declarations -/// Get frame id from message. nullptr_t is used to prevent template ambiguity on +/// Get frame id from message. std::nullptr_t is used to prevent template ambiguity on /// SFINAE specializations. Provide a default value on specializations for a friendly API. /// \tparam T Message type. /// \param msg Message. /// \return Frame id of the message. -template +template const std::string & get_frame_id(const T & msg) noexcept; -/// Get a reference to the frame id from message. nullptr_t is used to prevent +/// Get a reference to the frame id from message. std::nullptr_t is used to prevent /// template ambiguity on SFINAE specializations. Provide a default value on /// specializations for a friendly API. /// \tparam T Message type. /// \param msg Message. /// \return Frame id of the message. -template +template std::string & get_frame_id(T & msg) noexcept; -/// Get stamp from message. nullptr_t is used to prevent template ambiguity on +/// Get stamp from message. std::nullptr_t is used to prevent template ambiguity on /// SFINAE specializations. Provide a default value on specializations for a friendly API. /// \tparam T Message type. /// \param msg Message. /// \return Frame id of the message. -template +template const TimeStamp & get_stamp(const T & msg) noexcept; -/// Get a reference to the stamp from message. nullptr_t is used to prevent +/// Get a reference to the stamp from message. std::nullptr_t is used to prevent /// template ambiguity on SFINAE specializations. Provide a default value on /// specializations for a friendly API. /// \tparam T Message type. /// \param msg Message. /// \return Frame id of the message. -template +template TimeStamp & get_stamp(T & msg) noexcept; /////////////// Default specializations for message types that contain a header. -template ::value, nullptr_t>::type = nullptr> +template ::value, std::nullptr_t>::type = nullptr> const std::string & get_frame_id(const T & msg) noexcept { return msg.header.frame_id; } -template ::value, nullptr_t>::type = nullptr> +template ::value, std::nullptr_t>::type = nullptr> std::string & get_frame_id(T & msg) noexcept { return msg.header.frame_id; } -template ::value, nullptr_t>::type = nullptr> +template ::value, std::nullptr_t>::type = nullptr> TimeStamp & get_stamp(T & msg) noexcept { return msg.header.stamp; } -template ::value, nullptr_t>::type = nullptr> +template ::value, std::nullptr_t>::type = nullptr> TimeStamp get_stamp(const T & msg) noexcept { return msg.header.stamp; diff --git a/common/autoware_auto_geometry/CMakeLists.txt b/common/autoware_auto_geometry/CMakeLists.txt deleted file mode 100644 index ee819b7cd797c..0000000000000 --- a/common/autoware_auto_geometry/CMakeLists.txt +++ /dev/null @@ -1,39 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(autoware_auto_geometry) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -ament_auto_add_library(${PROJECT_NAME} SHARED - include/autoware_auto_geometry/spatial_hash.hpp - include/autoware_auto_geometry/intersection.hpp - include/autoware_auto_geometry/spatial_hash_config.hpp - src/spatial_hash.cpp - src/bounding_box.cpp -) - -if(BUILD_TESTING) - set(GEOMETRY_GTEST geometry_gtest) - set(GEOMETRY_SRC test/src/test_geometry.cpp - test/src/test_convex_hull.cpp - test/src/test_hull_pockets.cpp - test/src/test_interval.cpp - test/src/lookup_table.cpp - test/src/test_area.cpp - test/src/test_common_2d.cpp - test/src/test_intersection.cpp - ) - ament_add_ros_isolated_gtest(${GEOMETRY_GTEST} ${GEOMETRY_SRC}) - target_compile_options(${GEOMETRY_GTEST} PRIVATE -Wno-conversion -Wno-sign-conversion) - target_include_directories(${GEOMETRY_GTEST} PRIVATE "test/include" "include") - ament_target_dependencies(${GEOMETRY_GTEST} - "autoware_auto_common" - "autoware_auto_geometry_msgs" - "autoware_auto_planning_msgs" - "autoware_auto_vehicle_msgs" - "geometry_msgs" - "osrf_testing_tools_cpp") - target_link_libraries(${GEOMETRY_GTEST} ${PROJECT_NAME}) -endif() - -ament_auto_package() diff --git a/common/autoware_auto_geometry/design/interval.md b/common/autoware_auto_geometry/design/interval.md deleted file mode 100644 index 4fe65ff8e0310..0000000000000 --- a/common/autoware_auto_geometry/design/interval.md +++ /dev/null @@ -1,111 +0,0 @@ -# Interval - -The interval is a standard 1D real-valued interval. -The class implements a representation and operations on the interval type and guarantees interval validity on construction. -Basic operations and accessors are implemented, as well as other common operations. -See 'Example Usage' below. - -## Target use cases - -- Range or containment checks. - The interval class simplifies code that involves checking membership of a value to a range, or intersecting two ranges. - It also provides consistent behavior and consistent handling of edge cases. - -## Properties - -- **empty**: An empty interval is equivalent to an empty set. - It contains no elements. - It is a valid interval, but because it is empty, the notion of measure (length) is undefined; the measure of an empty interval is _not_ zero. - The implementation represents the measure of an empty interval with `NaN`. -- **zero measure**: An interval with zero measure is an interval whose bounds are exactly equal. - The measure is zero because the interval contains only a single point, and points have zero measure. - However, because it does contain a single element, the interval is _not_ empty. -- **valid**: A valid interval is either empty or has min/max bounds such that (min <= max). On construction, interval objects are guaranteed to be valid. - An attempt to construct an invalid interval results in a runtime_error exception being thrown. -- **pseudo-immutable**: Once constructed the only way to change the value of an interval is to overwrite it with a new one; an existing object cannot be modified. - -## Conventions - -- All operations on interval objects are defined as static class methods on the interval class. - This is a functional-style of programming that basically turns the class into a namespace that grants functions access to private member variables of the object they operate on. - -## Assumptions - -- The interval is only intended for floating point types. - This is enforced via static assertion. -- The constructor for non-empty intervals takes two arguments 'min' and 'max', and they must be ordered (i.e., min <= max). - If this assumption is violated, an exception is emitted and construction fails. - -## Example Usage - -```c++ -#include "autoware_auto_geometry/interval.hpp" - -#include - -// using-directive is just for illustration; don't do this in practice -using namespace autoware::common::geometry; - -// bounds for example interval -constexpr auto MIN = 0.0; -constexpr auto MAX = 1.0; - -// -// Try to construct an invalid interval. This will give the following error: -// 'Attempted to construct an invalid interval: {"min": 1.0, "max": 0.0}' -// - -try { - const auto i = Interval_d(MAX, MIN); -} catch (const std::runtime_error& e) { - std::cerr << e.what(); -} - -// -// Construct a double precision interval from 0 to 1 -// - -const auto i = Interval_d(MIN, MAX); - -// -// Test accessors and properties -// - -std::cout << Interval_d::min(i) << " " << Interval_d::max(i) << "\n"; -// Prints: 0.0 1.0 - -std::cout << Interval_d::empty(i) << " " << Interval_d::length(i) << "\n"; -// Prints: false 1.0 - -std::cout << Interval_d::contains(i, 0.3) << "\n"; -// Prints: true - -std::cout << Interval_d::is_subset_eq(Interval_d(0.2, 0.4), i) << "\n"; -// Prints: true - -// -// Test operations. -// - -std::cout << Interval_d::intersect(i, Interval(-1.0, 0.3)) << "\n"; -// Prints: {"min": 0.0, "max": 0.3} - -std::cout << Interval_d::project_to_interval(i, 0.5) << " " - << Interval_d::project_to_interval(i, -1.3) << "\n"; -// Prints: 0.5 0.0 - -// -// Distinguish empty/zero measure -// - -const auto i_empty = Interval(); -const auto i_zero_length = Interval(0.0, 0.0); - -std::cout << Interval_d::empty(i_empty) << " " - << Interval_d::empty(i_zero_length) << "\n"; -// Prints: true false - -std::cout << Interval_d::zero_measure(i_empty) << " " - << Interval_d::zero_measure(i_zero_length) << "\n"; -// Prints: false false -``` diff --git a/common/autoware_auto_geometry/design/polygon_intersection_2d-design.md b/common/autoware_auto_geometry/design/polygon_intersection_2d-design.md deleted file mode 100644 index f651c218bc80d..0000000000000 --- a/common/autoware_auto_geometry/design/polygon_intersection_2d-design.md +++ /dev/null @@ -1,51 +0,0 @@ -# 2D Convex Polygon Intersection - -Two convex polygon's intersection can be visualized on the image below as the blue area: - - - -## Purpose / Use cases - -Computing the intersection between two polygons can be useful in many applications of scene -understanding. It can be used to estimate collision detection, shape alignment, shape -association and in any application that deals with the objects around the perceiving agent. - -## Design - -[\(Livermore, Calif, 1977\)](https://doi.org/10.2172/7309916) mention the following -observations about convex polygon intersection: - -- Intersection of two convex polygons is a convex polygon -- A vertex from a polygon that is contained in the other polygon is a vertex of the intersection - shape. (Vertices A, C, D in the shape above) -- An edge from a polygon that is contained in the other polygon is an edge in the intersection - shape. (edge C-D in the shape above) -- Edge intersections between two polygons are vertices in the intersection shape. (Vertices B, - E in the shape above.) - -### Inner-workings / Algorithms - -With the observation mentioned above, the current algorithm operates in the following way: - -- Compute and find the vertices from each polygon that is contained in the other polygon - (Vertices A, C, D) -- Compute and find the intersection points between each polygon (Vertices B, E) -- Compute the convex hull shaped by these vertices by ordering them CCW. - -### Inputs / Outputs / API - -Inputs: - -- Two iterables that contain vertices of the convex polygons ordered in the CCW direction. - -Outputs: - -- A list of vertices of the intersection shape ordered in the CCW direction. - -## Future Work - -- #1230: Applying efficient algorithms. - -## Related issues - -- #983: Integrate vision detections in object tracker diff --git a/common/autoware_auto_geometry/design/spatial-hash-design.md b/common/autoware_auto_geometry/design/spatial-hash-design.md deleted file mode 100644 index 58eecf3ee841b..0000000000000 --- a/common/autoware_auto_geometry/design/spatial-hash-design.md +++ /dev/null @@ -1,99 +0,0 @@ -# Spatial Hash - -The spatial hash is a data structure designed for efficient fixed-radius near-neighbor queries in -low dimensions. - -The fixed-radius near-neighbors problem is defined as follows: - -`For point p, find all points p' s.t. d(p, p') < r` - -Where in this case `d(p, p')` is euclidean distance, and `r` is the fixed -radius. - -For `n` points with an average of `k` neighbors each, this data structure can -perform `m` near-neighbor queries (to generate lists of near-neighbors for `m` -different points) in `O(mk)` time. - -By contrast, using a k-d tree for successive nearest-neighbor queries results in -a running time of `O(m log n)`. - -The spatial hash works as follows: - -- Each point is assigned to a bin in the predefined bounding area defined by - `x_min/x_max` and `y_min/y_max` -- This can be done by converting x and y position into x and y index - respectively - - For example with the bin containing `x_min` and `y_min` as index `(0, 0)` - - The two (or more) indices can then be converted into a single index -- Once every point of interest has been inserted into the hash, near-neighbor - queries can begin: - - The bin of the reference point is first computed - - For each point in each adjacent bin, perform an explicit distance computation - between said point and the reference point. If the distance is below the given - radius, said point is considered to be a near-neighbor - -Under the hood, an `std::unordered_multimap` is used, where the key is a bin/voxel index. -The bin size was computed to be the same as the lookup distance. - - - -In addition, this data structure can support 2D or 3D queries. This is determined during -configuration, and baked into the data structure via the configuration class. The purpose of -this was to avoid if statements in tight loops. The configuration class specializations themselves -use CRTP (Curiously Recurring Template Patterns) to do "static polymorphism", and avoid -a dispatching call. - -## Performance characterization - -### Time - -Insertion is `O(n)` because lookup time for the underlying hashmap is `O(n)` for -hashmaps. In practice, lookup time for hashmaps and thus insertion time should -be `O(1)`. - -Removing a point is `O(1)` because the current API only supports removal via -direct reference to a node. - -Finding `k` near-neighbors is worst case `O(n)` in the case of an adversarial -example, but in practice `O(k)`. - -### Space - -The module consists of the following components: - -- The internal hashmap is `O(n + n + A * n)`, where `A` is an arbitrary - constant (load factor) -- The other components of the spatial hash are `O(n + n)` - -This results in `O(n)` space complexity. - -## States - -The spatial hash's state is dictated by the status of the underlying unordered_multimap. - -The data structure is wholly configured by a -[config](@ref autoware::common::geometry::spatial_hash::Config) class. The constructor -of the class determines in the data structure accepts strictly 2D or strictly 3D queries. - -## Inputs - -The primary method of introducing data into the data structure is via the -[insert](@ref autoware::common::geometry::spatial_hash::SpatialHashBase::insert) method. - -## Outputs - -The primary method of retrieving data from the data structure is via the -[near](@ref autoware::common::geometry::spatial_hash::SpatialHash::near)\(2D -configuration\) -or [near](@ref autoware::common::geometry::spatial_hash::SpatialHash::near) -\(3D configuration\) method. - -The whole data structure can also be traversed using standard constant iterators. - -## Future Work - -- Performance tuning and optimization - -## Related issues - -- #28: Port to autoware.Auto diff --git a/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box/bounding_box_common.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box/bounding_box_common.hpp deleted file mode 100644 index 0f3a68e14d442..0000000000000 --- a/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box/bounding_box_common.hpp +++ /dev/null @@ -1,188 +0,0 @@ -// Copyright 2017-2019 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. -// -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. - -/// \file -/// \brief Common functionality for bounding box computation algorithms - -#ifndef AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__BOUNDING_BOX_COMMON_HPP_ -#define AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__BOUNDING_BOX_COMMON_HPP_ - -#include "autoware_auto_geometry/common_2d.hpp" -#include "autoware_auto_geometry/visibility_control.hpp" - -#include -#include -#include -#include - -#include -#include -#include - -namespace autoware -{ -namespace common -{ -namespace geometry -{ -/// \brief Functions and types for generating enclosing bounding boxes around a set of points -namespace bounding_box -{ -using BoundingBox = autoware_auto_perception_msgs::msg::BoundingBox; - -/// \brief Computes height of bounding box given a full list of points -/// \param[in] begin The start of the list of points -/// \param[in] end One past the end of the list of points -/// \param[out] box A box for which the z component of centroid, corners, and size gets filled -/// \tparam IT An iterator type, must dereference into a point type with float member z, or -/// appropriate point adapter defined -template -void compute_height(const IT begin, const IT end, BoundingBox & box) -{ - float32_t max_z = -std::numeric_limits::max(); - float32_t min_z = std::numeric_limits::max(); - for (auto it = begin; it != end; ++it) { - const float32_t z = point_adapter::z_(*it); - if (z <= min_z) { - min_z = z; - } - if (z >= max_z) { - max_z = z; - } - } - box.centroid.z = (max_z + min_z) * 0.5F; - for (auto & corner : box.corners) { - corner.z = box.centroid.z; - } - box.size.z = (max_z - min_z) * 0.5F; -} - -/// \brief Computes height of bounding box given a full list of points -/// \param[in] begin Iterator pointing to the start of the range of points -/// \param[in] end Iterator pointing the the end of the range of points -/// \param[out] shape A shape in which vertices z values and height field will be set -/// \tparam IT An iterator type, must dereference into a point type with float member z, or -/// appropriate point adapter defined -template -void compute_height(const IT begin, const IT end, autoware_auto_perception_msgs::msg::Shape & shape) -{ - float32_t max_z = -std::numeric_limits::max(); - float32_t min_z = std::numeric_limits::max(); - for (auto it = begin; it != end; ++it) { - const float32_t z = point_adapter::z_(*it); - if (z <= min_z) { - min_z = z; - } - if (z >= max_z) { - max_z = z; - } - } - for (auto & corner : shape.footprint.points) { - corner.z = min_z; - } - shape.dimensions.z = max_z - min_z; -} - -namespace details -{ -/// Templated alias for getting a type without CV or reference qualification -template -using base_type = typename std::remove_cv::type>::type; - -/// Templated alias for an array of 4 objects of type PointT -template -using Point4 = std::array; - -/// \brief Helper struct for compile time introspection of array size from -/// Ref: https://stackoverflow.com/questions/16866033 -template -struct array_size; -template -struct array_size> -{ - static std::size_t const size = N; -}; -static_assert( - array_size>::size == 4U, - "Bounding box does not have the right number of corners"); - -/// \brief Compute length, width, area of bounding box -/// \param[in] corners Corners of the current bounding box -/// \param[out] ret A point struct used to hold size of box defined by corners -void GEOMETRY_PUBLIC -size_2d(const decltype(BoundingBox::corners) & corners, geometry_msgs::msg::Point32 & ret); -/// \brief Computes centroid and orientation of a box given corners -/// \param[in] corners Array of final corners of bounding box -/// \param[out] box Message to have corners, orientation, and centroid updated -void GEOMETRY_PUBLIC -finalize_box(const decltype(BoundingBox::corners) & corners, BoundingBox & box); - -/// \brief given support points and two orthogonal directions, compute corners of bounding box -/// \tparam PointT Type of a point, must have float members x and y` -/// \tparam IT An iterator dereferenceable into PointT -/// \param[out] corners Gets filled with corner points of bounding box -/// \param[in] supports Iterators referring to support points of current bounding box -/// e.g. bounding box is touching these points -/// \param[in] directions Directions of each edge of the bounding box from each support point -template -void compute_corners( - decltype(BoundingBox::corners) & corners, const Point4 & supports, - const Point4 & directions) -{ - for (uint32_t idx = 0U; idx < corners.size(); ++idx) { - const uint32_t jdx = (idx != 3U) ? (idx + 1U) : 0U; - const auto pt = - intersection_2d(*supports[idx], directions[idx], *supports[jdx], directions[jdx]); - // TODO(c.ho) handle error - point_adapter::xr_(corners[idx]) = point_adapter::x_(pt); - point_adapter::yr_(corners[idx]) = point_adapter::y_(pt); - } -} -// TODO(c.ho) type trait enum base - -/// \brief Copy vertices of the given box into a Shape type -/// \param box Box to be converted -/// \return Shape type filled with box vertices -autoware_auto_perception_msgs::msg::Shape GEOMETRY_PUBLIC make_shape(const BoundingBox & box); - -/// \brief Copy centroid and orientation info of the box into Pose type -/// \param box BoundingBox to be converted -/// \return Pose type filled with centroid and orientation from box -geometry_msgs::msg::Pose GEOMETRY_PUBLIC make_pose(const BoundingBox & box); - -/// \brief Fill DetectedObject type with contents from a BoundingBox type -/// \param box BoundingBox to be converted -/// \return Filled DetectedObject type -autoware_auto_perception_msgs::msg::DetectedObject GEOMETRY_PUBLIC -make_detected_object(const BoundingBox & box); - -/// \brief Transform corners from object-local coordinates using the given centroid and orientation -/// \param shape_msg Msg containing corners in object-local coordinates -/// \param centroid Centroid of the polygon whose corners are defined in shape_msg -/// \param orientation Orientation of the polygon -/// \return corners transformed such that their centroid and orientation correspond to the -/// given inputs -std::vector GEOMETRY_PUBLIC get_transformed_corners( - const autoware_auto_perception_msgs::msg::Shape & shape_msg, - const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation); - -} // namespace details -} // namespace bounding_box -} // namespace geometry -} // namespace common -} // namespace autoware - -#endif // AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__BOUNDING_BOX_COMMON_HPP_ diff --git a/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box/eigenbox_2d.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box/eigenbox_2d.hpp deleted file mode 100644 index e0f2e66e87ee5..0000000000000 --- a/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box/eigenbox_2d.hpp +++ /dev/null @@ -1,247 +0,0 @@ -// Copyright 2017-2019 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. -// -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. - -/// \file -/// \brief This file implements 2D pca on a linked list of points to estimate an oriented -/// bounding box - -// cspell: ignore eigenbox, EIGENBOX -#ifndef AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__EIGENBOX_2D_HPP_ -#define AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__EIGENBOX_2D_HPP_ - -#include "autoware_auto_geometry/bounding_box/bounding_box_common.hpp" - -#include -#include - -namespace autoware -{ -namespace common -{ -namespace geometry -{ -namespace bounding_box -{ -namespace details -{ - -/// \brief Simplified 2d covariance matrix -struct Covariance2d -{ - /// \brief Variance in the x direction - float32_t xx; - /// \brief Variance in the y direction - float32_t yy; - /// \brief x-y covariance - float32_t xy; - /// \brief Number of points - std::size_t num_points; -}; // struct Covariance2d - -// cspell: ignore Welford -/// \brief Compute 2d covariance matrix of a list of points using Welford's online algorithm -/// \param[in] begin An iterator pointing to the first point in a point list -/// \param[in] end An iterator pointing to one past the last point in the point list -/// \tparam IT An iterator type dereferenceable into a point with float members x and y -/// \return A 2d covariance matrix for all points in the list -template -Covariance2d covariance_2d(const IT begin, const IT end) -{ - Covariance2d ret{0.0F, 0.0F, 0.0F, 0U}; - float32_t ux = 0.0F; - float32_t uy = 0.0F; - float32_t num_points = 0.0F; - using point_adapter::x_; - using point_adapter::y_; - for (auto it = begin; it != end; ++it) { - ++ret.num_points; - num_points = static_cast(ret.num_points); - const auto & pt = *it; - // update mean x - const float32_t dx = x_(pt) - ux; - ux = ux + (dx / num_points); - // update cov - const float32_t dy = y_(pt) - uy; - ret.xy += (x_(pt) - ux) * (dy); - // update mean y - uy = uy + (dy / num_points); - // update M2 - ret.xx += dx * (x_(pt) - ux); - ret.yy += dy * (y_(pt) - uy); - } - // finalize sample (co-)variance - if (ret.num_points > 1U) { - num_points = num_points - 1.0F; - } - ret.xx /= num_points; - ret.yy /= num_points; - ret.xy /= num_points; - - return ret; -} - -/// \brief Compute eigenvectors and eigenvalues -/// \param[in] cov 2d Covariance matrix -/// \param[out] eig_vec1 First eigenvector -/// \param[out] eig_vec2 Second eigenvector -/// \tparam PointT Point type that has at least float members x and y -/// \return A pair of eigenvalues: The first is the larger eigenvalue -/// \throw std::runtime error if you would get degenerate covariance -template -std::pair eig_2d( - const Covariance2d & cov, PointT & eig_vec1, PointT & eig_vec2) -{ - const float32_t tr_2 = (cov.xx + cov.yy) * 0.5F; - const float32_t det = (cov.xx * cov.yy) - (cov.xy * cov.xy); - // Add a small fudge to alleviate floating point errors - float32_t disc = ((tr_2 * tr_2) - det) + std::numeric_limits::epsilon(); - if (disc < 0.0F) { - throw std::runtime_error( - "pca_2d: negative discriminant! Should never happen for well formed " - "covariance matrix"); - } - disc = sqrtf(disc); - // compute eigenvalues - const auto ret = std::make_pair(tr_2 + disc, tr_2 - disc); - // compute eigenvectors - using point_adapter::xr_; - using point_adapter::yr_; - // We compare squared value against floating epsilon to make sure that eigen vectors - // are persistent against further calculations. - // (e.g. taking cross product of two eigen vectors) - if (fabsf(cov.xy * cov.xy) > std::numeric_limits::epsilon()) { - xr_(eig_vec1) = cov.xy; - yr_(eig_vec1) = ret.first - cov.xx; - xr_(eig_vec2) = cov.xy; - yr_(eig_vec2) = ret.second - cov.xx; - } else { - if (cov.xx > cov.yy) { - xr_(eig_vec1) = 1.0F; - yr_(eig_vec1) = 0.0F; - xr_(eig_vec2) = 0.0F; - yr_(eig_vec2) = 1.0F; - } else { - xr_(eig_vec1) = 0.0F; - yr_(eig_vec1) = 1.0F; - xr_(eig_vec2) = 1.0F; - yr_(eig_vec2) = 0.0F; - } - } - return ret; -} - -/// \brief Given eigenvectors, compute support (furthest) point in each direction -/// \tparam IT An iterator type dereferenceable into a point with float members x and y -/// \tparam PointT type of a point with float members x and y -/// \param[in] begin An iterator pointing to the first point in a point list -/// \param[in] end An iterator pointing to one past the last point in the point list -/// \param[in] eig1 First principal component of cluster -/// \param[in] eig2 Second principal component of cluster -/// \param[out] support Array to get filled with extreme points in each of the principal -/// components -/// \return whether or not eig2 is ccw wrt eig1 -template -bool8_t compute_supports( - const IT begin, const IT end, const PointT & eig1, const PointT & eig2, Point4 & support) -{ - const bool8_t ret = cross_2d(eig1, eig2) >= 0.0F; - std::array metrics{ - {-std::numeric_limits::max(), -std::numeric_limits::max(), - std::numeric_limits::max(), std::numeric_limits::max()}}; - for (auto it = begin; it != end; ++it) { - const PointT & pt = *it; - float32_t val = dot_2d(ret ? eig1 : eig2, pt); - if (val > metrics[0U]) { - metrics[0U] = val; - support[0U] = it; - } - if (val < metrics[2U]) { - metrics[2U] = val; - support[2U] = it; - } - val = dot_2d(ret ? eig2 : eig1, pt); - if (val > metrics[1U]) { - metrics[1U] = val; - support[1U] = it; - } - if (val < metrics[3U]) { - metrics[3U] = val; - support[3U] = it; - } - } - return ret; -} - -/// \brief Compute bounding box given a pair of basis directions -/// \tparam IT An iterator type dereferenceable into a point with float members x and y -/// \tparam PointT Point type of the lists, must have float members x and y -/// \param[in] ax1 First basis direction, assumed to be normal to ax2 -/// \param[in] ax2 Second basis direction, assumed to be normal to ax1, assumed to be ccw wrt ax1 -/// \param[in] supports Array of iterators referring to points that are most extreme in each basis -/// direction. Should be result of compute_supports function -/// \return A bounding box based on the basis axes and the support points -template -BoundingBox compute_bounding_box( - const PointT & ax1, const PointT & ax2, const Point4 & supports) -{ - decltype(BoundingBox::corners) corners; - const Point4 directions{{ax1, ax2, minus_2d(ax1), minus_2d(ax2)}}; - compute_corners(corners, supports, directions); - - // build box - BoundingBox bbox; - finalize_box(corners, bbox); - size_2d(corners, bbox.size); - return bbox; -} -} // namespace details - -/// \brief Compute oriented bounding box using PCA. This uses all points in a list, and does not -/// modify the list. The resulting bounding box is not necessarily minimum in any way -/// \param[in] begin An iterator pointing to the first point in a point list -/// \param[in] end An iterator pointing to one past the last point in the point list -/// \tparam IT An iterator type dereferenceable into a point with float members x and y -/// \return An oriented bounding box in x-y. This bounding box has no height information -template -BoundingBox eigenbox_2d(const IT begin, const IT end) -{ - // compute covariance - const details::Covariance2d cov = details::covariance_2d(begin, end); - - // compute eigenvectors - using PointT = details::base_type; - PointT eig1; - PointT eig2; - const auto eig_v = details::eig_2d(cov, eig1, eig2); - - // find extreme points - details::Point4 supports; - const bool8_t is_ccw = details::compute_supports(begin, end, eig1, eig2, supports); - // build box - if (is_ccw) { - std::swap(eig1, eig2); - } - BoundingBox bbox = details::compute_bounding_box(eig1, eig2, supports); - bbox.value = eig_v.first; - - return bbox; -} -} // namespace bounding_box -} // namespace geometry -} // namespace common -} // namespace autoware - -#endif // AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__EIGENBOX_2D_HPP_ diff --git a/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box/lfit.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box/lfit.hpp deleted file mode 100644 index 07fd6c989cedc..0000000000000 --- a/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box/lfit.hpp +++ /dev/null @@ -1,281 +0,0 @@ -// Copyright 2017-2019 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. -// -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. - -/// \file -/// \brief This file implements 2D pca on a linked list of points to estimate an oriented -/// bounding box - -// cspell: ignore LFIT, lfit -// LFIT means "L-Shape Fitting" -#ifndef AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__LFIT_HPP_ -#define AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__LFIT_HPP_ - -#include "autoware_auto_geometry/bounding_box/eigenbox_2d.hpp" - -#include -#include - -namespace autoware -{ -namespace common -{ -namespace geometry -{ -namespace bounding_box -{ -namespace details -{ - -/// \brief A representation of the M matrix for the L-fit algorithm -struct LFitWs -{ - /// \brief Number of points in the first partition - std::size_t p; - /// \brief Number of points in the second partition - std::size_t q; - // assume matrix of form: [a b; c d] - /// \brief Sum of x values in first partition - float32_t m12a; - /// \brief Sum of y values in first partition - float32_t m12b; - /// \brief Sum of y values in second partition - float32_t m12c; - /// \brief Negative sum of x values in second partition - float32_t m12d; - // m22 is a symmetric matrix - /// \brief Sum_p x_2 + sum_q y_2 - float32_t m22a; - /// \brief Sum_p x*y - sum_q x*y - float32_t m22b; - /// \brief Sum_p y_2 + sum_x y_2 - float32_t m22d; -}; // struct LFitWs - -/// \brief Initialize M matrix for L-fit algorithm -/// \param[in] begin An iterator pointing to the first point in a point list -/// \param[in] end An iterator one past the last point in the point list -/// \param[in] size The number of points in the point list -/// \param[out] ws A representation of the M matrix to get initialized -/// \tparam IT The iterator type, should dereference to a point type with float members x and y -template -void init_lfit_ws(const IT begin, const IT end, const std::size_t size, LFitWs & ws) -{ - ws.p = 1UL; - ws.q = size - 1UL; - // init P terms (first partition) - using point_adapter::x_; - using point_adapter::y_; - const auto & pt = *begin; - const float32_t px = x_(pt); - const float32_t py = y_(pt); - // assume matrix of form: [a b; c d] - ws.m12a = px; - ws.m12b = py; - ws.m12c = 0.0F; - ws.m12d = 0.0F; - // m22 is a symmetric matrix - ws.m22a = px * px; - ws.m22b = px * py; - ws.m22d = py * py; - auto it = begin; - ++it; - for (; it != end; ++it) { - const auto & qt = *it; - const float32_t qx = x_(qt); - const float32_t qy = y_(qt); - ws.m12c += qy; - ws.m12d -= qx; - ws.m22a += qy * qy; - ws.m22b -= qx * qy; - ws.m22d += qx * qx; - } -} - -/// \brief Solves the L fit problem for a given M matrix -/// \tparam PointT The point type of the cluster being L-fitted -/// \param[in] ws A representation of the M Matrix -/// \param[out] dir The best fit direction for this partition/M matrix -/// \return The L2 residual for this fit (the score, lower is better) -template -float32_t solve_lfit(const LFitWs & ws, PointT & dir) -{ - const float32_t pi = 1.0F / static_cast(ws.p); - const float32_t qi = 1.0F / static_cast(ws.q); - const Covariance2d M{// matrix of form [x, z; z y] - ws.m22a - (((ws.m12a * ws.m12a) * pi) + ((ws.m12c * ws.m12c) * qi)), - ws.m22d - (((ws.m12b * ws.m12b) * pi) + ((ws.m12d * ws.m12d) * qi)), - ws.m22b - (((ws.m12a * ws.m12b) * pi) + ((ws.m12c * ws.m12d) * qi)), 0UL}; - PointT eig1; - const auto eig_v = eig_2d(M, eig1, dir); - return eig_v.second; -} - -/// \brief Increments L fit M matrix with information in the point -/// \tparam PointT The point type -/// \param[in] pt The point to increment the M matrix with -/// \param[inout] ws A representation of the M matrix -template -void increment_lfit_ws(const PointT & pt, LFitWs & ws) -{ - const float32_t px = point_adapter::x_(pt); - const float32_t py = point_adapter::y_(pt); - ws.m12a += px; - ws.m12b += py; - ws.m12c -= py; - ws.m12d += px; - ws.m22b += 2.0F * px * py; - const float32_t px2y2 = (px - py) * (px + py); - ws.m22a += px2y2; - ws.m22d -= px2y2; -} - -/// \tparam IT An iterator type that should dereference into a point type with float members x and y -template -class LFitCompare -{ -public: - /// \brief Constructor, initializes normal direction - /// \param[in] hint A 2d vector with the direction that will be used to order the - /// point list - explicit LFitCompare(const PointT & hint) - : m_nx(point_adapter::x_(hint)), m_ny(point_adapter::y_(hint)) - { - } - - /// \brief Comparator operation, returns true if the projection of a the tangent line - /// is smaller than the projection of b - /// \param[in] p The first point for comparison - /// \param[in] q The second point for comparison - /// \return True if a has a smaller projection than b on the tangent line - bool8_t operator()(const PointT & p, const PointT & q) const - { - using point_adapter::x_; - using point_adapter::y_; - return ((x_(p) * m_nx) + (y_(p) * m_ny)) < ((x_(q) * m_nx) + (y_(q) * m_ny)); - } - -private: - const float32_t m_nx; - const float32_t m_ny; -}; // class LFitCompare - -/// \brief The main implementation of L-fitting a bounding box to a list of points. -/// Assumes sufficiently valid, large enough, and appropriately ordered point list -/// \param[in] begin An iterator pointing to the first point in a point list -/// \param[in] end An iterator pointing to one past the last point in the point list -/// \param[in] size The number of points in the point list -/// \return A bounding box that minimizes the LFit residual -/// \tparam IT An iterator type dereferenceable into a point with float members x and y -template -BoundingBox lfit_bounding_box_2d_impl(const IT begin, const IT end, const std::size_t size) -{ - // initialize M - LFitWs ws{}; - init_lfit_ws(begin, end, size, ws); - // solve initial problem - details::base_type best_normal; - float32_t min_eig = solve_lfit(ws, best_normal); - // solve subsequent problems - auto it = begin; - ++it; - for (; it != end; ++it) { - // update M - ws.p += 1U; - ws.q -= 1U; - if (ws.q == 0U) { // checks for q = 0 case - break; - } - increment_lfit_ws(*it, ws); - // solve incremented problem - decltype(best_normal) dir; - const float32_t score = solve_lfit(ws, dir); - // update optima - if (score < min_eig) { - min_eig = score; - best_normal = dir; - } - } - // can recover best corner point, but don't care, need to cover all points - const auto inv_norm = 1.0F / norm_2d(best_normal); - if (!std::isnormal(inv_norm)) { - throw std::runtime_error{"LFit: Abnormal norm"}; - } - best_normal = times_2d(best_normal, inv_norm); - auto best_tangent = get_normal(best_normal); - // find extreme points - Point4 supports; - const bool8_t is_ccw = details::compute_supports(begin, end, best_normal, best_tangent, supports); - if (is_ccw) { - std::swap(best_normal, best_tangent); - } - BoundingBox bbox = details::compute_bounding_box(best_normal, best_tangent, supports); - bbox.value = min_eig; - - return bbox; -} -} // namespace details - -/// \brief Compute bounding box which best fits an L-shaped cluster. Uses the method proposed -/// in "Efficient L-shape fitting of laser scanner data for vehicle pose estimation" -/// \return An oriented bounding box in x-y. This bounding box has no height information -/// \param[in] begin An iterator pointing to the first point in a point list -/// \param[in] end An iterator pointing to one past the last point in the point list -/// \param[in] size The number of points in the point list -/// \param[in] hint An iterator pointing to the point whose normal will be used to sort the list -/// \return A pair where the first element is an iterator pointing to the nearest point, and the -/// second element is the size of the list -/// \tparam IT An iterator type dereferenceable into a point with float members x and y -/// \throw std::domain_error If the number of points is too few -template -BoundingBox lfit_bounding_box_2d( - const IT begin, const IT end, const PointT hint, const std::size_t size) -{ - if (size <= 1U) { - throw std::domain_error("LFit requires >= 2 points!"); - } - // NOTE: assumes points are in base_link/sensor frame! - // sort along tangent wrt sensor origin - // lint -e522 NOLINT Not a pure function: data structure iterators are pointing to is modified - std::partial_sort(begin, end, end, details::LFitCompare{hint}); - - return details::lfit_bounding_box_2d_impl(begin, end, size); -} - -/// \brief Compute bounding box which best fits an L-shaped cluster. Uses the method proposed -/// in "Efficient L-shape fitting of laser scanner data for vehicle pose estimation". -/// This implementation sorts the list using std::sort -/// \return An oriented bounding box in x-y. This bounding box has no height information -/// \param[in] begin An iterator pointing to the first point in a point list -/// \param[in] end An iterator pointing to one past the last point in the point list -/// \tparam IT An iterator type dereferenceable into a point with float members x and y -template -BoundingBox lfit_bounding_box_2d(const IT begin, const IT end) -{ - // use the principal component as the sorting direction - const auto cov = details::covariance_2d(begin, end); - using PointT = details::base_type; - PointT eig1; - PointT eig2; - (void)details::eig_2d(cov, eig1, eig2); - (void)eig2; - return lfit_bounding_box_2d(begin, end, eig1, cov.num_points); -} -} // namespace bounding_box -} // namespace geometry -} // namespace common -} // namespace autoware - -#endif // AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__LFIT_HPP_ diff --git a/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box/rotating_calipers.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box/rotating_calipers.hpp deleted file mode 100644 index fb75384eb07cb..0000000000000 --- a/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box/rotating_calipers.hpp +++ /dev/null @@ -1,280 +0,0 @@ -// Copyright 2017-2019 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. -// -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. - -/// \file -/// \brief This file implements the rotating calipers algorithm for minimum oriented bounding boxes - -#ifndef AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__ROTATING_CALIPERS_HPP_ -#define AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__ROTATING_CALIPERS_HPP_ -#include "autoware_auto_geometry/bounding_box/bounding_box_common.hpp" -#include "autoware_auto_geometry/common_2d.hpp" -#include "autoware_auto_geometry/convex_hull.hpp" - -#include -#include -#include -#include - -namespace autoware -{ -namespace common -{ -namespace geometry -{ -namespace bounding_box -{ -namespace details -{ -/// \brief Find which (next) edge has smallest angle delta to directions, rotate directions -/// \param[inout] edges Array of edges on polygon after each anchor point (in ccw order). -/// E.g. if anchor point = p_i, edge = P[i+1] - P[i] -/// \param[inout] directions Array of directions of current bounding box (in ccw order) -/// \tparam PointT Point type of the lists, must have float members x and y -/// \return index of array to advance, e.g. the one with the smallest angle between edge and dir -template -uint32_t update_angles(const Point4 & edges, Point4 & directions) -{ - // find smallest angle to next - float32_t best_cos_th = -std::numeric_limits::max(); - float32_t best_edge_dir_mag = 0.0F; - uint32_t advance_idx = 0U; - for (uint32_t idx = 0U; idx < edges.size(); ++idx) { - const float32_t edge_dir_mag = std::max( - norm_2d(edges[idx]) * norm_2d(directions[idx]), std::numeric_limits::epsilon()); - const float32_t cos_th = dot_2d(edges[idx], directions[idx]) / edge_dir_mag; - if (cos_th > best_cos_th) { - best_cos_th = cos_th; - best_edge_dir_mag = edge_dir_mag; - advance_idx = idx; - } - } - - // update directions by smallest angle - const float32_t sin_th = - cross_2d(directions[advance_idx], edges[advance_idx]) / best_edge_dir_mag; - for (uint32_t idx = 0U; idx < edges.size(); ++idx) { - rotate_2d(directions[idx], best_cos_th, sin_th); - } - - return advance_idx; -} - -/// \brief Given support points i, find direction of edge: e = P[i+1] - P[i] -/// \tparam PointT Point type of the lists, must have float members x and y -/// \tparam IT The iterator type, should dereference to a point type with float members x and y -/// \param[in] begin An iterator pointing to the first point in a point list -/// \param[in] end An iterator pointing to one past the last point in the point list -/// \param[in] support Array of points that are most extreme in 4 directions for current OBB -/// \param[out] edges An array to be filled with the polygon edges next from support points -template -void init_edges(const IT begin, const IT end, const Point4 & support, Point4 & edges) -{ - for (uint32_t idx = 0U; idx < support.size(); ++idx) { - auto tmp_it = support[idx]; - ++tmp_it; - const PointT & q = (tmp_it == end) ? *begin : *tmp_it; - edges[idx] = minus_2d(q, *support[idx]); - } -} - -/// \brief Scan through list to find support points for bounding box oriented in direction of -/// u = P[1] - P[0] -/// \tparam IT The iterator type, should dereference to a point type with float members x and y -/// \param[in] begin An iterator pointing to the first point in a point list -/// \param[in] end An iterator pointing to one past the last point in the point list -/// \param[out] support Array that gets filled with pointers to points that are most extreme in -/// each direction aligned with and orthogonal to the first polygon edge. -/// Most extreme = max/min wrt u = P[1]-P[0] (in the dot/cross product sense) -template -void init_bbox(const IT begin, const IT end, Point4 & support) -{ - // compute initial orientation using first two points - auto pt_it = begin; - ++pt_it; - const auto u = minus_2d(*pt_it, *begin); - support[0U] = begin; - std::array metric{ - {-std::numeric_limits::max(), -std::numeric_limits::max(), - std::numeric_limits::max()}}; - // track u * p, fabsf(u x p), and -u * p - for (pt_it = begin; pt_it != end; ++pt_it) { - // check points against orientation for run_ptr - const auto & pt = *pt_it; - // u * p - const float32_t up = dot_2d(u, pt); - if (up > metric[0U]) { - metric[0U] = up; - support[1U] = pt_it; - } - // -u * p - if (up < metric[2U]) { - metric[2U] = up; - support[3U] = pt_it; - } - // u x p - const float32_t uxp = cross_2d(u, pt); - if (uxp > metric[1U]) { - metric[1U] = uxp; - support[2U] = pt_it; - } - } -} -/// \brief Compute the minimum bounding box for a convex hull using the rotating calipers method. -/// This function may possibly also be used for computing the width of a convex hull, as it uses the -/// external supports of a single convex hull. -/// \param[in] begin An iterator to the first point on a convex hull -/// \param[in] end An iterator to one past the last point on a convex hull -/// \param[in] metric_fn A functor determining what measure the bounding box is minimum with respect -/// to -/// \tparam IT An iterator type dereferenceable into a point type with float members x and y -/// \tparam MetricF A functor that computes a float measure from the x and y size (width and length) -/// of a bounding box, assumed to be packed in a Point32 message. -/// \throw std::domain_error if the list of points is too small to reasonable generate a bounding -/// box -template -BoundingBox rotating_calipers_impl(const IT begin, const IT end, const MetricF metric_fn) -{ - using PointT = base_type; - // sanity check TODO(c.ho) more checks (up to n = 2?) - if (begin == end) { - throw std::domain_error("Malformed list, size = " + std::to_string(std::distance(begin, end))); - } - // initial scan to get anchor points - Point4 support; - init_bbox(begin, end, support); - // initialize directions accordingly - Point4 directions; - { // I just don't want the temporary variable floating around - auto tmp = support[0U]; - ++tmp; - directions[0U] = minus_2d(*tmp, *support[0U]); - directions[1U] = get_normal(directions[0U]); - directions[2U] = minus_2d(directions[0U]); - directions[3U] = minus_2d(directions[1U]); - } - // initialize edges - Point4 edges; - init_edges(begin, end, support, edges); - // size of initial guess - BoundingBox bbox; - decltype(BoundingBox::corners) best_corners; - compute_corners(best_corners, support, directions); - size_2d(best_corners, bbox.size); - bbox.value = metric_fn(bbox.size); - // rotating calipers step: incrementally advance, update angles, points, compute area - for (auto it = begin; it != end; ++it) { - // find smallest angle to next, update directions - const uint32_t advance_idx = update_angles(edges, directions); - // recompute area - decltype(BoundingBox::corners) corners; - compute_corners(corners, support, directions); - decltype(BoundingBox::size) tmp_size; - size_2d(corners, tmp_size); - const float32_t tmp_value = metric_fn(tmp_size); - // update best if necessary - if (tmp_value < bbox.value) { - // corners: memcpy is fine since I know corners and best_corners are distinct - (void)std::memcpy(&best_corners[0U], &corners[0U], sizeof(corners)); - // size - bbox.size = tmp_size; - bbox.value = tmp_value; - } - // Step to next iteration of calipers - { - // update smallest support - auto next_it = support[advance_idx]; - ++next_it; - const auto run_it = (end == next_it) ? begin : next_it; - support[advance_idx] = run_it; - // update edges - next_it = run_it; - ++next_it; - const PointT & next = (end == next_it) ? (*begin) : (*next_it); - edges[advance_idx] = minus_2d(next, *run_it); - } - } - - finalize_box(best_corners, bbox); - - // TODO(christopher.ho) check if one of the sizes is too small, fuzz corner 1 and 2 - // This doesn't cause any issues now, it shouldn't happen in practice, and even if it did, - // it would probably get smoothed out by prediction. But, this could cause issues with the - // collision detection algorithms (i.e GJK), but probably not. - - return bbox; -} -} // namespace details - -/// \brief Compute the minimum area bounding box given a convex hull of points. -/// This function is exposed in case a user might already have a convex hull via other methods. -/// \param[in] begin An iterator to the first point on a convex hull -/// \param[in] end An iterator to one past the last point on a convex hull -/// \return A minimum area bounding box, value field is the area -/// \tparam IT An iterator type dereferenceable into a point type with float members x and y -template -BoundingBox minimum_area_bounding_box(const IT begin, const IT end) -{ - const auto metric_fn = [](const decltype(BoundingBox::size) & pt) -> float32_t { - return pt.x * pt.y; - }; - return details::rotating_calipers_impl(begin, end, metric_fn); -} - -/// \brief Compute the minimum perimeter bounding box given a convex hull of points -/// This function is exposed in case a user might already have a convex hull via other methods. -/// \param[in] begin An iterator to the first point on a convex hull -/// \param[in] end An iterator to one past the last point on a convex hull -/// \return A minimum perimeter bounding box, value field is half the perimeter -/// \tparam IT An iterator type dereferenceable into a point type with float members x and y -template -BoundingBox minimum_perimeter_bounding_box(const IT begin, const IT end) -{ - const auto metric_fn = [](const decltype(BoundingBox::size) & pt) -> float32_t { - return pt.x + pt.y; - }; - return details::rotating_calipers_impl(begin, end, metric_fn); -} - -/// \brief Compute the minimum area bounding box given an unstructured list of points. -/// Only a list is supported as it enables the convex hull to be formed in O(n log n) time and -/// without memory allocation. -/// \param[inout] list A list of points to form a hull around, gets reordered -/// \return A minimum area bounding box, value field is the area -/// \tparam PointT Point type of the lists, must have float members x and y -template -BoundingBox minimum_area_bounding_box(std::list & list) -{ - const auto last = convex_hull(list); - return minimum_area_bounding_box(list.cbegin(), last); -} - -/// \brief Compute the minimum perimeter bounding box given an unstructured list of points -/// Only a list is supported as it enables the convex hull to be formed in O(n log n) time and -/// without memory allocation. -/// \param[inout] list A list of points to form a hull around, gets reordered -/// \return A minimum perimeter bounding box, value field is half the perimeter -/// \tparam PointT Point type of the lists, must have float members x and y -template -BoundingBox minimum_perimeter_bounding_box(std::list & list) -{ - const auto last = convex_hull(list); - return minimum_perimeter_bounding_box(list.cbegin(), last); -} -} // namespace bounding_box -} // namespace geometry -} // namespace common -} // namespace autoware -#endif // AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX__ROTATING_CALIPERS_HPP_ diff --git a/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box_2d.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box_2d.hpp deleted file mode 100644 index c4c52928ac19a..0000000000000 --- a/common/autoware_auto_geometry/include/autoware_auto_geometry/bounding_box_2d.hpp +++ /dev/null @@ -1,34 +0,0 @@ -// Copyright 2017-2020 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. -// -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. -/// \file -/// \brief Main header for user-facing bounding box algorithms: functions and types -#ifndef AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX_2D_HPP_ -#define AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX_2D_HPP_ - -#include "autoware_auto_geometry/bounding_box/eigenbox_2d.hpp" -#include "autoware_auto_geometry/bounding_box/lfit.hpp" -#include "autoware_auto_geometry/bounding_box/rotating_calipers.hpp" - -namespace autoware -{ -namespace common -{ -namespace geometry -{ -} // namespace geometry -} // namespace common -} // namespace autoware -#endif // AUTOWARE_AUTO_GEOMETRY__BOUNDING_BOX_2D_HPP_ diff --git a/common/autoware_auto_geometry/include/autoware_auto_geometry/common_2d.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/common_2d.hpp deleted file mode 100644 index e3c2e58c9f80e..0000000000000 --- a/common/autoware_auto_geometry/include/autoware_auto_geometry/common_2d.hpp +++ /dev/null @@ -1,587 +0,0 @@ -// Copyright 2017-2021 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. -// -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. -/// \file -/// \brief This file includes common functionality for 2D geometry, such as dot products - -#ifndef AUTOWARE_AUTO_GEOMETRY__COMMON_2D_HPP_ -#define AUTOWARE_AUTO_GEOMETRY__COMMON_2D_HPP_ - -#include "autoware_auto_geometry/interval.hpp" - -#include - -#include "autoware_auto_planning_msgs/msg/trajectory_point.hpp" - -#include -#include -#include - -using autoware::common::types::bool8_t; -using autoware::common::types::float32_t; - -namespace comparison = autoware::common::helper_functions::comparisons; - -namespace autoware -{ -namespace common -{ -namespace geometry -{ - -/// \brief Temporary namespace for point adapter methods, for use with nonstandard point types -namespace point_adapter -{ -/// \brief Gets the x value for a point -/// \return The x value of the point -/// \param[in] pt The point -/// \tparam PointT The point type -template -inline auto x_(const PointT & pt) -{ - return pt.x; -} -/// \brief Gets the x value for a TrajectoryPoint message -/// \return The x value of the point -/// \param[in] pt The point -inline auto x_(const autoware_auto_planning_msgs::msg::TrajectoryPoint & pt) -{ - return pt.pose.position.x; -} -/// \brief Gets the y value for a point -/// \return The y value of the point -/// \param[in] pt The point -/// \tparam PointT The point type -template -inline auto y_(const PointT & pt) -{ - return pt.y; -} -/// \brief Gets the y value for a TrajectoryPoint message -/// \return The y value of the point -/// \param[in] pt The point -inline auto y_(const autoware_auto_planning_msgs::msg::TrajectoryPoint & pt) -{ - return pt.pose.position.y; -} -/// \brief Gets the z value for a point -/// \return The z value of the point -/// \param[in] pt The point -/// \tparam PointT The point type -template -inline auto z_(const PointT & pt) -{ - return pt.z; -} -/// \brief Gets the z value for a TrajectoryPoint message -/// \return The z value of the point -/// \param[in] pt The point -inline auto z_(const autoware_auto_planning_msgs::msg::TrajectoryPoint & pt) -{ - return pt.pose.position.z; -} -/// \brief Gets a reference to the x value for a point -/// \return A reference to the x value of the point -/// \param[in] pt The point -/// \tparam PointT The point type -template -inline auto & xr_(PointT & pt) -{ - return pt.x; -} -/// \brief Gets a reference to the x value for a TrajectoryPoint -/// \return A reference to the x value of the TrajectoryPoint -/// \param[in] pt The TrajectoryPoint -inline auto & xr_(autoware_auto_planning_msgs::msg::TrajectoryPoint & pt) -{ - return pt.pose.position.x; -} -/// \brief Gets a reference to the y value for a point -/// \return A reference to The y value of the point -/// \param[in] pt The point -/// \tparam PointT The point type -template -inline auto & yr_(PointT & pt) -{ - return pt.y; -} -/// \brief Gets a reference to the y value for a TrajectoryPoint -/// \return A reference to the y value of the TrajectoryPoint -/// \param[in] pt The TrajectoryPoint -inline auto & yr_(autoware_auto_planning_msgs::msg::TrajectoryPoint & pt) -{ - return pt.pose.position.y; -} -/// \brief Gets a reference to the z value for a point -/// \return A reference to the z value of the point -/// \param[in] pt The point -/// \tparam PointT The point type -template -inline auto & zr_(PointT & pt) -{ - return pt.z; -} -/// \brief Gets a reference to the z value for a TrajectoryPoint -/// \return A reference to the z value of the TrajectoryPoint -/// \param[in] pt The TrajectoryPoint -inline auto & zr_(autoware_auto_planning_msgs::msg::TrajectoryPoint & pt) -{ - return pt.pose.position.z; -} -} // namespace point_adapter - -namespace details -{ -// Return the next iterator, cycling back to the beginning of the list if you hit the end -template -IT circular_next(const IT begin, const IT end, const IT current) noexcept -{ - auto next = std::next(current); - if (end == next) { - next = begin; - } - return next; -} - -} // namespace details - -/// \tparam T1, T2, T3 point type. Must have point adapters defined or have float members x and y -/// \brief compute whether line segment rp is counter clockwise relative to line segment qp -/// \param[in] pt shared point for both line segments -/// \param[in] r point to check if it forms a ccw angle -/// \param[in] q reference point -/// \return whether angle formed is ccw. Three collinear points is considered ccw -template -inline auto ccw(const T1 & pt, const T2 & q, const T3 & r) -{ - using point_adapter::x_; - using point_adapter::y_; - return (((x_(q) - x_(pt)) * (y_(r) - y_(pt))) - ((y_(q) - y_(pt)) * (x_(r) - x_(pt)))) <= 0.0F; -} - -/// \tparam T1, T2 point type. Must have point adapters defined or have float members x and y -/// \brief compute p x q = p1 * q2 - p2 * q1 -/// \param[in] pt first point -/// \param[in] q second point -/// \return 2d cross product -template -inline auto cross_2d(const T1 & pt, const T2 & q) -{ - using point_adapter::x_; - using point_adapter::y_; - return (x_(pt) * y_(q)) - (y_(pt) * x_(q)); -} - -/// \tparam T1, T2 point type. Must have point adapters defined or have float members x and y -/// \brief compute p * q = p1 * q1 + p2 * q2 -/// \param[in] pt first point -/// \param[in] q second point -/// \return 2d scalar dot product -template -inline auto dot_2d(const T1 & pt, const T2 & q) -{ - using point_adapter::x_; - using point_adapter::y_; - return (x_(pt) * x_(q)) + (y_(pt) * y_(q)); -} - -/// \tparam T point type. Must have point adapters defined or have float members x and y -/// \brief Compute the 2d difference between two points, p - q -/// \param[in] p The left hand side -/// \param[in] q The right hand side -/// \return A point with the difference in the x and y fields, all other fields are default -/// initialized -template -T minus_2d(const T & p, const T & q) -{ - T r; - using point_adapter::x_; - using point_adapter::y_; - point_adapter::xr_(r) = x_(p) - x_(q); - point_adapter::yr_(r) = y_(p) - y_(q); - return r; -} - -/// \tparam T point type. Must have point adapters defined or have float members x and y -/// \brief The unary minus or negation operator applied to a single point's 2d fields -/// \param[in] p The left hand side -/// \return A point with the negation in the x and y fields, all other fields are default -/// initialized -template -T minus_2d(const T & p) -{ - T r; - point_adapter::xr_(r) = -point_adapter::x_(p); - point_adapter::yr_(r) = -point_adapter::y_(p); - return r; -} -/// \tparam T point type. Must have point adapters defined or have float members x and y -/// \brief The 2d addition operation, p + q -/// \param[in] p The left hand side -/// \param[in] q The right hand side -/// \return A point with the sum in the x and y fields, all other fields are default -/// initialized -template -T plus_2d(const T & p, const T & q) -{ - T r; - using point_adapter::x_; - using point_adapter::y_; - point_adapter::xr_(r) = x_(p) + x_(q); - point_adapter::yr_(r) = y_(p) + y_(q); - return r; -} - -/// \tparam T point type. Must have point adapters defined or have float members x and y -/// \brief The scalar multiplication operation, p * a -/// \param[in] p The point value -/// \param[in] a The scalar value -/// \return A point with the scaled x and y fields, all other fields are default -/// initialized -template -T times_2d(const T & p, const float32_t a) -{ - T r; - point_adapter::xr_(r) = static_cast(point_adapter::x_(p)) * a; - point_adapter::yr_(r) = static_cast(point_adapter::y_(p)) * a; - return r; -} - -/// \tparam T point type. Must have point adapters defined or have float members x and y -/// \brief solve p + t * u = q + s * v -/// Ref: https://stackoverflow.com/questions/563198/ -/// \param[in] pt anchor point of first line -/// \param[in] u direction of first line -/// \param[in] q anchor point of second line -/// \param[in] v direction of second line -/// \return intersection point -/// \throw std::runtime_error if lines are (nearly) collinear or parallel -template -inline T intersection_2d(const T & pt, const T & u, const T & q, const T & v) -{ - const float32_t num = cross_2d(minus_2d(pt, q), u); - float32_t den = cross_2d(v, u); - // cspell: ignore FEPS - // FEPS means "Float EPSilon" - constexpr auto FEPS = std::numeric_limits::epsilon(); - if (fabsf(den) < FEPS) { - if (fabsf(num) < FEPS) { - // collinear case, anything is ok - den = 1.0F; - } else { - // parallel case, no valid output - throw std::runtime_error( - "intersection_2d: no unique solution (either collinear or parallel)"); - } - } - return plus_2d(q, times_2d(v, num / den)); -} - -/// \tparam T point type. Must have point adapters defined or have float members x and y -/// \brief rotate point given precomputed sin and cos -/// \param[inout] pt point to rotate -/// \param[in] cos_th precomputed cosine value -/// \param[in] sin_th precomputed sine value -template -inline void rotate_2d(T & pt, const float32_t cos_th, const float32_t sin_th) -{ - const float32_t x = point_adapter::x_(pt); - const float32_t y = point_adapter::y_(pt); - point_adapter::xr_(pt) = (cos_th * x) - (sin_th * y); - point_adapter::yr_(pt) = (sin_th * x) + (cos_th * y); -} - -/// \tparam T point type. Must have point adapters defined or have float members x and y -/// \brief rotate by radian angle th in z direction with ccw positive -/// \param[in] pt reference point to rotate -/// \param[in] th_rad angle by which to rotate point -/// \return rotated point -template -inline T rotate_2d(const T & pt, const float32_t th_rad) -{ - T q(pt); // It's reasonable to expect a copy constructor - const float32_t s = sinf(th_rad); - const float32_t c = cosf(th_rad); - rotate_2d(q, c, s); - return q; -} - -/// \tparam T point type. Must have point adapters defined or have float members x and y -/// \brief compute q s.t. p T q, or p * q = 0 -/// This is the equivalent of a 90 degree ccw rotation -/// \param[in] pt point to get normal point of -/// \return point normal to p (un-normalized) -template -inline T get_normal(const T & pt) -{ - T q(pt); - point_adapter::xr_(q) = -point_adapter::y_(pt); - point_adapter::yr_(q) = point_adapter::x_(pt); - return q; -} - -/// \tparam T point type. Must have point adapters defined or have float members x and y -/// \brief get magnitude of x and y components: -/// \param[in] pt point to get magnitude of -/// \return magnitude of x and y components together -template -inline auto norm_2d(const T & pt) -{ - return sqrtf(static_cast(dot_2d(pt, pt))); -} - -/// \tparam T point type. Must have point adapters defined or have float members x and y -/// \brief Compute the closest point on line segment p-q to point r -/// Based on equations from https://stackoverflow.com/a/1501725 and -/// http://paulbourke.net/geometry/pointlineplane/ -/// \param[in] p First point defining the line segment -/// \param[in] q Second point defining the line segment -/// \param[in] r Reference point to find the closest point to -/// \return Closest point on line segment p-q to point r -template -inline T closest_segment_point_2d(const T & p, const T & q, const T & r) -{ - const T qp = minus_2d(q, p); - const float32_t len2 = static_cast(dot_2d(qp, qp)); - T ret = p; - if (len2 > std::numeric_limits::epsilon()) { - const Interval_f unit_interval(0.0f, 1.0f); - const float32_t val = static_cast(dot_2d(minus_2d(r, p), qp)) / len2; - const float32_t t = Interval_f::clamp_to(unit_interval, val); - ret = plus_2d(p, times_2d(qp, t)); - } - return ret; -} -// -/// \tparam T point type. Must have point adapters defined or have float members x and y -/// \brief Compute the closest point on the line going through p-q to point r -// Obtained by simplifying closest_segment_point_2d. -/// \param[in] p First point defining the line -/// \param[in] q Second point defining the line -/// \param[in] r Reference point to find the closest point to -/// \return Closest point on line p-q to point r -/// \throw std::runtime_error if the two points coincide and hence don't uniquely -// define a line -template -inline T closest_line_point_2d(const T & p, const T & q, const T & r) -{ - const T qp = minus_2d(q, p); - const float32_t len2 = dot_2d(qp, qp); - T ret = p; - if (len2 > std::numeric_limits::epsilon()) { - const float32_t t = dot_2d(minus_2d(r, p), qp) / len2; - ret = plus_2d(p, times_2d(qp, t)); - } else { - throw std::runtime_error( - "closet_line_point_2d: line ill-defined because given points coincide"); - } - return ret; -} - -/// \tparam T point type. Must have point adapters defined or have float members x and y -/// \brief Compute the distance from line segment p-q to point r -/// \param[in] p First point defining the line segment -/// \param[in] q Second point defining the line segment -/// \param[in] r Reference point to find the distance from the line segment to -/// \return Distance from point r to line segment p-q -template -inline auto point_line_segment_distance_2d(const T & p, const T & q, const T & r) -{ - const T pq_r = minus_2d(closest_segment_point_2d(p, q, r), r); - return norm_2d(pq_r); -} - -/// \brief Make a 2D unit vector given an angle. -/// \tparam T Point type. Must have point adapters defined or have float members x and y -/// \param th Angle in radians -/// \return Unit vector in the direction of the given angle. -template -inline T make_unit_vector2d(float th) -{ - T r; - point_adapter::xr_(r) = std::cos(th); - point_adapter::yr_(r) = std::sin(th); - return r; -} - -/// \brief Compute squared euclidean distance between two points -/// \tparam OUT return type. Type of the returned distance. -/// \tparam T1 point type. Must have point adapters defined or have float members x and y -/// \tparam T2 point type. Must have point adapters defined or have float members x and y -/// \param a point 1 -/// \param b point 2 -/// \return squared euclidean distance -template -inline OUT squared_distance_2d(const T1 & a, const T2 & b) -{ - const auto x = static_cast(point_adapter::x_(a)) - static_cast(point_adapter::x_(b)); - const auto y = static_cast(point_adapter::y_(a)) - static_cast(point_adapter::y_(b)); - return (x * x) + (y * y); -} - -/// \brief Compute euclidean distance between two points -/// \tparam OUT return type. Type of the returned distance. -/// \tparam T1 point type. Must have point adapters defined or have float members x and y -/// \tparam T2 point type. Must have point adapters defined or have float members x and y -/// \param a point 1 -/// \param b point 2 -/// \return euclidean distance -template -inline OUT distance_2d(const T1 & a, const T2 & b) -{ - return std::sqrt(squared_distance_2d(a, b)); -} - -/// \brief Check the given point's position relative the infinite line passing -/// from p1 to p2. Logic based on http://geomalgorithms.com/a01-_area.html#isLeft() -/// \tparam T T point type. Must have point adapters defined or have float members x and y -/// \param p1 point 1 laying on the infinite line -/// \param p2 point 2 laying on the infinite line -/// \param q point to be checked against the line -/// \return > 0 for point q left of the line through p1 to p2 -/// = 0 for point q on the line through p1 to p2 -/// < 0 for point q right of the line through p1 to p2 -template -inline auto check_point_position_to_line_2d(const T & p1, const T & p2, const T & q) -{ - return cross_2d(minus_2d(p2, p1), minus_2d(q, p1)); -} - -/// Check if all points are ordered in x-y plane (in either clockwise or counter-clockwise -/// direction): This function does not check for convexity -/// \tparam IT Iterator type pointing to a point containing float x and float y -/// \param[in] begin Beginning of point sequence -/// \param[in] end One past the last of the point sequence -/// \return Whether or not all point triples p_i, p_{i+1}, p_{i+2} are in a particular order. -/// Returns true for collinear points as well -template -bool all_ordered(const IT begin, const IT end) noexcept -{ - // Short circuit: a line or point is always CCW or otherwise ill-defined - if (std::distance(begin, end) <= 2U) { - return true; - } - bool is_first_point_cw = false; - // Can't use std::all_of because that works directly on the values - for (auto line_start = begin; line_start != end; ++line_start) { - const auto line_end = details::circular_next(begin, end, line_start); - const auto query_point = details::circular_next(begin, end, line_end); - // Check if 3 points starting from current point are in clockwise direction - const bool is_cw = comparison::abs_lte( - check_point_position_to_line_2d(*line_start, *line_end, *query_point), 0.0F, 1e-3F); - if (is_cw) { - if (line_start == begin) { - is_first_point_cw = true; - } else { - if (!is_first_point_cw) { - return false; - } - } - } else if (is_first_point_cw) { - return false; - } - } - return true; -} - -/// Compute the area of a convex hull, points are assumed to be ordered (in either CW or CCW) -/// \tparam IT Iterator type pointing to a point containing float x and float y -/// \param[in] begin Iterator pointing to the beginning of the polygon points -/// \param[in] end Iterator pointing to one past the last of the polygon points -/// \return The area of the polygon, in squared of whatever units your points are in -template -auto area_2d(const IT begin, const IT end) noexcept -{ - using point_adapter::x_; - using point_adapter::y_; - using T = decltype(x_(*begin)); - auto area = T{}; // zero initialization - // use the approach of https://www.mathwords.com/a/area_convex_polygon.htm - for (auto it = begin; it != end; ++it) { - const auto next = details::circular_next(begin, end, it); - area += x_(*it) * y_(*next); - area -= x_(*next) * y_(*it); - } - return std::abs(T{0.5} * area); -} - -/// Compute area of convex hull, throw if points are not ordered (convexity check is not -/// implemented) -/// \throw std::domain_error if points are not ordered either CW or CCW -/// \tparam IT Iterator type pointing to a point containing float x and float y -/// \param[in] begin Iterator pointing to the beginning of the polygon points -/// \param[in] end Iterator pointing to one past the last of the polygon points -/// \return The area of the polygon, in squared of whatever units your points are in -template -auto area_checked_2d(const IT begin, const IT end) -{ - if (!all_ordered(begin, end)) { - throw std::domain_error{"Cannot compute area: points are not ordered"}; - } - return area_2d(begin, end); -} - -/// \brief Check if the given point is inside or on the edge of the given polygon -/// \tparam IteratorType iterator type. The value pointed to by this must have point adapters -/// defined or have float members x and y -/// \tparam PointType point type. Must have point adapters defined or have float members x and y -/// \param start_it iterator pointing to the first vertex of the polygon -/// \param end_it iterator pointing to the last vertex of the polygon. The vertices should be in -/// order. -/// \param p point to be searched -/// \return True if the point is inside or on the edge of the polygon. False otherwise -template -bool is_point_inside_polygon_2d( - const IteratorType & start_it, const IteratorType & end_it, const PointType & p) -{ - std::int32_t winding_num = 0; - - for (IteratorType it = start_it; it != end_it; ++it) { - auto next_it = std::next(it); - if (next_it == end_it) { - next_it = start_it; - } - if (point_adapter::y_(*it) <= point_adapter::y_(p)) { - // Upward crossing edge - if (point_adapter::y_(*next_it) >= point_adapter::y_(p)) { - if (comparison::abs_gt(check_point_position_to_line_2d(*it, *next_it, p), 0.0F, 1e-3F)) { - ++winding_num; - } else { - if (comparison::abs_eq_zero(check_point_position_to_line_2d(*it, *next_it, p), 1e-3F)) { - return true; - } - } - } - } else { - // Downward crossing edge - if (point_adapter::y_(*next_it) <= point_adapter::y_(p)) { - if (comparison::abs_lt(check_point_position_to_line_2d(*it, *next_it, p), 0.0F, 1e-3F)) { - --winding_num; - } else { - if (comparison::abs_eq_zero(check_point_position_to_line_2d(*it, *next_it, p), 1e-3F)) { - return true; - } - } - } - } - } - return winding_num != 0; -} - -} // namespace geometry -} // namespace common -} // namespace autoware - -#endif // AUTOWARE_AUTO_GEOMETRY__COMMON_2D_HPP_ diff --git a/common/autoware_auto_geometry/include/autoware_auto_geometry/common_3d.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/common_3d.hpp deleted file mode 100644 index 74cd210dec586..0000000000000 --- a/common/autoware_auto_geometry/include/autoware_auto_geometry/common_3d.hpp +++ /dev/null @@ -1,77 +0,0 @@ -// Copyright 2017-2019 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. -// -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. -/// \file -/// \brief This file includes common functionality for 3D geometry, such as dot products - -#ifndef AUTOWARE_AUTO_GEOMETRY__COMMON_3D_HPP_ -#define AUTOWARE_AUTO_GEOMETRY__COMMON_3D_HPP_ - -#include "autoware_auto_geometry/common_2d.hpp" - -namespace autoware -{ -namespace common -{ -namespace geometry -{ - -/// \tparam T1, T2 point type. Must have point adapters defined or have float members x, y and z -/// \brief compute p * q = p1 * q1 + p2 * q2 + p3 * 13 -/// \param[in] pt first point -/// \param[in] q second point -/// \return 3d scalar dot product -template -inline auto dot_3d(const T1 & pt, const T2 & q) -{ - using point_adapter::x_; - using point_adapter::y_; - using point_adapter::z_; - return (x_(pt) * x_(q)) + (y_(pt) * y_(q) + z_(pt) * z_(q)); -} - -/// \brief Compute 3D squared euclidean distance between two points -/// \tparam OUT return type. Type of the returned distance. -/// \tparam T1 point type. Must have point adapters defined or have float members x y and z -/// \tparam T2 point type. Must have point adapters defined or have float members x y and z -/// \param a point 1 -/// \param b point 2 -/// \return squared 3D euclidean distance -template -inline OUT squared_distance_3d(const T1 & a, const T2 & b) -{ - const auto x = static_cast(point_adapter::x_(a)) - static_cast(point_adapter::x_(b)); - const auto y = static_cast(point_adapter::y_(a)) - static_cast(point_adapter::y_(b)); - const auto z = static_cast(point_adapter::z_(a)) - static_cast(point_adapter::z_(b)); - return (x * x) + (y * y) + (z * z); -} - -/// \brief Compute 3D euclidean distance between two points -/// \tparam T1 point type. Must have point adapters defined or have float members x y and z -/// \tparam T2 point type. Must have point adapters defined or have float members x y and z -/// \param a point 1 -/// \param b point 2 -/// \return 3D euclidean distance -template -inline OUT distance_3d(const T1 & a, const T2 & b) -{ - return std::sqrt(squared_distance_3d(a, b)); -} - -} // namespace geometry -} // namespace common -} // namespace autoware - -#endif // AUTOWARE_AUTO_GEOMETRY__COMMON_3D_HPP_ diff --git a/common/autoware_auto_geometry/include/autoware_auto_geometry/convex_hull.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/convex_hull.hpp deleted file mode 100644 index ae81c55ad6b55..0000000000000 --- a/common/autoware_auto_geometry/include/autoware_auto_geometry/convex_hull.hpp +++ /dev/null @@ -1,195 +0,0 @@ -// Copyright 2017-2019 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. -// -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. - -/// \file -/// \brief This file implements the monotone chain algorithm to compute 2D convex hulls on linked -/// lists of points - -#ifndef AUTOWARE_AUTO_GEOMETRY__CONVEX_HULL_HPP_ -#define AUTOWARE_AUTO_GEOMETRY__CONVEX_HULL_HPP_ - -#include "autoware_auto_geometry/common_2d.hpp" - -#include - -// lint -e537 NOLINT pclint vs cpplint -#include -// lint -e537 NOLINT pclint vs cpplint -#include -#include -#include - -using autoware::common::types::float32_t; - -namespace autoware -{ -namespace common -{ -namespace geometry -{ -/// \brief Contains computation geometry functions not intended for the end user to directly use -namespace details -{ - -/// \brief Moves points comprising the lower convex hull from points to hull. -/// \param[inout] points A list of points, assumed to be sorted in lexical order -/// \param[inout] hull An empty list of points, assumed to have same allocator as points -/// (for splice) -/// \tparam PointT The point type for the points list -/// \tparam HullT the point type for the hull list -template -void form_lower_hull(std::list & points, std::list & hull) -{ - auto hull_it = hull.cbegin(); - auto point_it = points.cbegin(); - // This ensures that the points we splice to back to the end of list are not processed - const auto iters = points.size(); - for (auto idx = decltype(iters){0}; idx < iters; ++idx) { - // splice points from tail of hull to tail of list until point from head of list satisfies ccw - bool8_t is_ccw = true; - while ((hull.cbegin() != hull_it) && is_ccw) { - const auto current_hull_it = hull_it; - --hull_it; - is_ccw = ccw(*hull_it, *current_hull_it, *point_it); - if (!is_ccw) { - hull_it = current_hull_it; - break; - } - // return this node to list for consideration in upper hull - points.splice(points.end(), hull, current_hull_it); - } - const auto last_point_it = point_it; - ++point_it; - // Splice head of list to tail of (lower) hull - hull.splice(hull.end(), points, last_point_it); - // point_it has been advanced, hull_it has been advanced (to where point_it was previously) - hull_it = last_point_it; - } - // loop is guaranteed not to underflow because a node can be removed from points AT MOST once - // per loop iteration. The loop is upper bounded to the prior size of the point list -} -/// \brief Moves points comprising the lower convex hull from points to hull. -/// \param[inout] points A list of points, assumed to be sorted in lexical order, and to contain -/// the leftmost point -/// \param[inout] hull A list of points, assumed to have same allocator as points (for splice), -/// and to contain the lower hull (minus the left-most point) -/// \tparam PointT The point type for the points list -/// \tparam HullT the point type for the hull list -template -void form_upper_hull(std::list & points, std::list & hull) -{ - // TODO(c.ho) consider reverse iterators, not sure if they work with splice() - auto hull_it = hull.cend(); - --hull_it; - const auto lower_hull_end = hull_it; - auto point_it = points.cend(); - --point_it; - // This ensures that the points we splice to back to the head of list are not processed - const auto iters = points.size(); - for (auto idx = decltype(iters){0}; idx < iters; ++idx) { - // splice points from tail of hull to head of list until ccw is satisfied with tail of list - bool8_t is_ccw = true; - while ((lower_hull_end != hull_it) && is_ccw) { - const auto current_hull_it = hull_it; - --hull_it; - is_ccw = ccw(*hull_it, *current_hull_it, *point_it); - if (!is_ccw) { - hull_it = current_hull_it; - break; - } - points.splice(points.begin(), hull, current_hull_it); - } - const auto last_point_it = point_it; - --point_it; - // Splice points from tail of lexically ordered point list to tail of hull - hull.splice(hull.end(), points, last_point_it); - hull_it = last_point_it; - } - // loop is guaranteed not to underflow because a node can be removed from points AT MOST once - // per loop iteration. The loop is upper bounded to the prior size of the point list -} - -/// \brief A static memory implementation of convex hull computation. Shuffles points around the -/// deque such that the points of the convex hull of the deque of points are first in the -/// deque, with the internal points following in an unspecified order. -/// The head of the deque will be the point with the smallest x value, with the other -/// points following in a counter-clockwise manner (from a top down view/facing -z direction) -/// \param[inout] list A list of nodes that will be pruned down and reordered into a ccw convex hull -/// \return An iterator pointing to one after the last point contained in the hull -/// \tparam PointT Type of a point, must have x and y float members -template -typename std::list::const_iterator convex_hull_impl(std::list & list) -{ - // Functor that return whether a <= b in the lexical sense (a.x < b.x), sort by y if tied - const auto lexical_comparator = [](const PointT & a, const PointT & b) -> bool8_t { - using point_adapter::x_; - using point_adapter::y_; - // cspell: ignore FEPS - // FEPS means "Float EPSilon" - constexpr auto FEPS = std::numeric_limits::epsilon(); - return (fabsf(x_(a) - x_(b)) > FEPS) ? (x_(a) < x_(b)) : (y_(a) < y_(b)); - }; - list.sort(lexical_comparator); - - // Temporary list to store points - std::list tmp_hull_list{list.get_allocator()}; - - // Shuffle lower hull points over to tmp_hull_list - form_lower_hull(list, tmp_hull_list); - - // Resort list since we can't guarantee the order TODO(c.ho) is this true? - list.sort(lexical_comparator); - // splice first hull point to beginning of list to ensure upper hull is properly closed - // This is done after sorting because we know exactly where it should go, and keeping it out of - // sorting reduces complexity somewhat - list.splice(list.begin(), tmp_hull_list, tmp_hull_list.begin()); - - // build upper hull - form_upper_hull(list, tmp_hull_list); - // Move hull to beginning of list, return iterator pointing to one after the convex hull - const auto ret = list.begin(); - // first move left-most point to ensure it is first - auto tmp_it = tmp_hull_list.end(); - --tmp_it; - list.splice(list.begin(), tmp_hull_list, tmp_it); - // Then move remainder of hull points - list.splice(ret, tmp_hull_list); - return ret; -} -} // namespace details - -/// \brief A static memory implementation of convex hull computation. Shuffles points around the -/// deque such that the points of the convex hull of the deque of points are first in the -/// deque, with the internal points following in an unspecified order. -/// -/// The head of the deque will be the point with the smallest x value, with the other -/// points following in a counter-clockwise manner (from a top down view/facing -z -/// direction). If the point list is 3 or smaller, nothing is done (e.g. the ordering result -/// as previously stated does not hold). -/// \param[inout] list A list of nodes that will be reordered into a ccw convex hull -/// \return An iterator pointing to one after the last point contained in the hull -/// \tparam PointT Type of a point, must have x and y float members -template -typename std::list::const_iterator convex_hull(std::list & list) -{ - return (list.size() <= 3U) ? list.end() : details::convex_hull_impl(list); -} - -} // namespace geometry -} // namespace common -} // namespace autoware - -#endif // AUTOWARE_AUTO_GEOMETRY__CONVEX_HULL_HPP_ diff --git a/common/autoware_auto_geometry/include/autoware_auto_geometry/hull_pockets.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/hull_pockets.hpp deleted file mode 100644 index cd9fd49f71635..0000000000000 --- a/common/autoware_auto_geometry/include/autoware_auto_geometry/hull_pockets.hpp +++ /dev/null @@ -1,111 +0,0 @@ -// Copyright 2020 Embotech AG, Zurich, Switzerland. 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. -// -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. - -/// \file -/// \brief This file implements an algorithm for getting a list of "pockets" in the convex -/// hull of a non-convex simple polygon. - -#ifndef AUTOWARE_AUTO_GEOMETRY__HULL_POCKETS_HPP_ -#define AUTOWARE_AUTO_GEOMETRY__HULL_POCKETS_HPP_ - -#include "autoware_auto_geometry/common_2d.hpp" - -#include - -#include -#include -#include -#include -#include - -using autoware::common::types::float32_t; - -namespace autoware -{ -namespace common -{ -namespace geometry -{ - -/// \brief Compute a list of "pockets" of a simple polygon -/// (https://en.wikipedia.org/wiki/Simple_polygon), that is, the areas that make -/// up the difference between the polygon and its convex hull. -/// This currently has a bug: -// * "Rollover" is not properly handled - if a pocket contains the segment from -// the last point in the list to the first point (which is still part of the -// polygon), that does not get added -/// -/// \param[in] polygon_start Start iterator for the simple polygon (has to be on convex hull) -/// \param[in] polygon_end End iterator for the simple polygon -/// \param[in] convex_hull_start Start iterator for the convex hull of the simple polygon -/// \param[in] convex_hull_end End iterator for the convex hull of the simple polygon -/// \return A vector of vectors of the iterator value type. Each inner vector contains the points -/// for one pocket. We return by value instead of as iterator pairs, because it is possible -/// that the edge connecting the final point in the list and the first point in the list is -/// part of a pocket as well, and this is awkward to represent using iterators into the -/// original collection. -/// -/// \tparam Iter1 Iterator to a point type -/// \tparam Iter2 Iterator to a point type (can be the same as Iter1, but does not need to be) -template -typename std::vector::value_type>> hull_pockets( - const Iter1 polygon_start, const Iter1 polygon_end, const Iter2 convex_hull_start, - const Iter2 convex_hull_end) -{ - auto pockets = std::vector::value_type>>{}; - if (std::distance(polygon_start, polygon_end) <= 3) { - return pockets; - } - - // Function to check whether a point is in the convex hull. - const auto in_convex_hull = [convex_hull_start, convex_hull_end](Iter1 p) { - return std::any_of(convex_hull_start, convex_hull_end, [p](auto hull_entry) { - return norm_2d(minus_2d(hull_entry, *p)) < std::numeric_limits::epsilon(); - }); - }; - - // We go through the points of the polygon only once, adding pockets to the list of pockets - // as we detect them. - std::vector::value_type> current_pocket{}; - for (auto it = polygon_start; it != polygon_end; it = std::next(it)) { - if (in_convex_hull(it)) { - if (current_pocket.size() > 1) { - current_pocket.emplace_back(*it); - pockets.push_back(current_pocket); - } - current_pocket.clear(); - current_pocket.emplace_back(*it); - } else { - current_pocket.emplace_back(*it); - } - } - - // At this point, we have reached the end of the polygon, but have not considered the connection - // of the final point back to the first. In case the first point is part of a pocket as well, we - // have some points left in current_pocket, and we add one final pocket that is made up by those - // points plus the first point in the collection. - if (current_pocket.size() > 1) { - current_pocket.push_back(*polygon_start); - pockets.push_back(current_pocket); - } - - return pockets; -} -} // namespace geometry -} // namespace common -} // namespace autoware - -#endif // AUTOWARE_AUTO_GEOMETRY__HULL_POCKETS_HPP_ diff --git a/common/autoware_auto_geometry/include/autoware_auto_geometry/intersection.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/intersection.hpp deleted file mode 100644 index 08c70c3a5a6be..0000000000000 --- a/common/autoware_auto_geometry/include/autoware_auto_geometry/intersection.hpp +++ /dev/null @@ -1,312 +0,0 @@ -// Copyright 2020 Embotech AG, Zurich, Switzerland -// -// 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. -// -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. - -#ifndef AUTOWARE_AUTO_GEOMETRY__INTERSECTION_HPP_ -#define AUTOWARE_AUTO_GEOMETRY__INTERSECTION_HPP_ - -#include "autoware_auto_geometry/common_2d.hpp" -#include "autoware_auto_geometry/convex_hull.hpp" - -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include - -namespace autoware -{ -namespace common -{ -namespace geometry -{ -using autoware::common::geometry::closest_line_point_2d; -using autoware::common::geometry::convex_hull; -using autoware::common::geometry::dot_2d; -using autoware::common::geometry::get_normal; -using autoware::common::geometry::minus_2d; -using autoware::common::geometry::norm_2d; -using autoware::common::geometry::times_2d; -using autoware_auto_perception_msgs::msg::BoundingBox; -using autoware_auto_planning_msgs::msg::TrajectoryPoint; - -using Point = geometry_msgs::msg::Point32; - -namespace details -{ - -/// Alias for a std::pair of two points -using Line = std::pair; - -/// \tparam Iter1 Iterator over point-types that must have point adapters -// defined or have float members x and y -/// \brief Compute a sorted list of faces of a polyhedron given a list of points -/// \param[in] start Start iterator of the list of points -/// \param[in] end End iterator of the list of points -/// \return The list of faces -template -std::vector get_sorted_face_list(const Iter start, const Iter end) -{ - // First get a sorted list of points - convex_hull does that by modifying its argument - auto corner_list = std::list(start, end); - const auto first_interior_point = convex_hull(corner_list); - - std::vector face_list{}; - auto itLast = corner_list.begin(); - auto itNext = std::next(itLast, 1); - do { - face_list.emplace_back(Line{*itLast, *itNext}); - itLast = itNext; - itNext = std::next(itNext, 1); - } while ((itNext != first_interior_point) && (itNext != corner_list.end())); - - face_list.emplace_back(Line{*itLast, corner_list.front()}); - - return face_list; -} - -/// \brief Append points of the polygon `internal` that are contained in the polygon `external`. -template < - template class Iterable1T, template class Iterable2T, typename PointT> -void append_contained_points( - const Iterable1T & external, const Iterable2T & internal, - std::list & result) -{ - std::copy_if( - internal.begin(), internal.end(), std::back_inserter(result), [&external](const auto & pt) { - return common::geometry::is_point_inside_polygon_2d(external.begin(), external.end(), pt); - }); -} - -/// \brief Append the intersecting points between two polygons into the output list. -template < - template class Iterable1T, template class Iterable2T, typename PointT> -void append_intersection_points( - const Iterable1T & polygon1, const Iterable2T & polygon2, - std::list & result) -{ - using FloatT = decltype(point_adapter::x_(std::declval())); - using Interval = common::geometry::Interval; - - auto get_edge = [](const auto & list, const auto & iterator) { - const auto next_it = std::next(iterator); - const auto & next_pt = (next_it != list.end()) ? *next_it : list.front(); - return std::make_pair(*iterator, next_pt); - }; - - // Get the max absolute value out of two intervals and a scalar. - auto compute_eps_scale = [](const auto & i1, const auto & i2, const auto val) { - auto get_abs_max = [](const auto & interval) { - return std::max(std::fabs(Interval::min(interval)), std::fabs(Interval::max(interval))); - }; - return std::max(std::fabs(val), std::max(get_abs_max(i1), get_abs_max(i2))); - }; - - // Compare each edge from polygon1 to each edge from polygon2 - for (auto corner1_it = polygon1.begin(); corner1_it != polygon1.end(); ++corner1_it) { - const auto & edge1 = get_edge(polygon1, corner1_it); - - Interval edge1_x_interval{ - std::min(point_adapter::x_(edge1.first), point_adapter::x_(edge1.second)), - std::max(point_adapter::x_(edge1.first), point_adapter::x_(edge1.second))}; - - Interval edge1_y_interval{ - std::min(point_adapter::y_(edge1.first), point_adapter::y_(edge1.second)), - std::max(point_adapter::y_(edge1.first), point_adapter::y_(edge1.second))}; - - for (auto corner2_it = polygon2.begin(); corner2_it != polygon2.end(); ++corner2_it) { - try { - const auto & edge2 = get_edge(polygon2, corner2_it); - const auto & intersection = common::geometry::intersection_2d( - edge1.first, minus_2d(edge1.second, edge1.first), edge2.first, - minus_2d(edge2.second, edge2.first)); - - Interval edge2_x_interval{ - std::min(point_adapter::x_(edge2.first), point_adapter::x_(edge2.second)), - std::max(point_adapter::x_(edge2.first), point_adapter::x_(edge2.second))}; - - Interval edge2_y_interval{ - std::min(point_adapter::y_(edge2.first), point_adapter::y_(edge2.second)), - std::max(point_adapter::y_(edge2.first), point_adapter::y_(edge2.second))}; - - // cspell: ignore feps - // feps means "Float EPSilon" - - // The accumulated floating point error depends on the magnitudes of each end of the - // intervals. Hence the upper bound of the absolute magnitude should be taken into account - // while computing the epsilon. - const auto max_feps_scale = std::max( - compute_eps_scale(edge1_x_interval, edge2_x_interval, point_adapter::x_(intersection)), - compute_eps_scale(edge1_y_interval, edge2_y_interval, point_adapter::y_(intersection))); - const auto feps = max_feps_scale * std::numeric_limits::epsilon(); - // Only accept intersections that lie on both of the line segments (edges) - if ( - Interval::contains(edge1_x_interval, point_adapter::x_(intersection), feps) && - Interval::contains(edge2_x_interval, point_adapter::x_(intersection), feps) && - Interval::contains(edge1_y_interval, point_adapter::y_(intersection), feps) && - Interval::contains(edge2_y_interval, point_adapter::y_(intersection), feps)) { - result.push_back(intersection); - } - } catch (const std::runtime_error &) { - // Parallel lines. TODO(yunus.caliskan): #1229 - continue; - } - } - } -} - -} // namespace details - -// TODO(s.me) implement GJK(+EPA) algorithm as well as per Chris Ho's suggestion -/// \tparam Iter Iterator over point-types that must have point adapters -// defined or have float members x and y -/// \brief Check if polyhedra defined by two given sets of points intersect -// This uses SAT for doing the actual checking -// (https://en.wikipedia.org/wiki/Hyperplane_separation_theorem#Use_in_collision_detection) -/// \param[in] begin1 Start iterator to first list of point types -/// \param[in] end1 End iterator to first list of point types -/// \param[in] begin2 Start iterator to first list of point types -/// \param[in] end2 End iterator to first list of point types -/// \return true if the boxes collide, false otherwise. -template -bool intersect(const Iter begin1, const Iter end1, const Iter begin2, const Iter end2) -{ - // Obtain sorted lists of faces of both boxes, merge them into one big list of faces - auto faces = details::get_sorted_face_list(begin1, end1); - const auto faces_2 = details::get_sorted_face_list(begin2, end2); - faces.reserve(faces.size() + faces_2.size()); - faces.insert(faces.end(), faces_2.begin(), faces_2.end()); - - // Also look at last line - for (const auto & face : faces) { - // Compute normal vector to the face and define a closure to get progress along it - const auto normal = get_normal(minus_2d(face.second, face.first)); - auto get_position_along_line = [&normal](auto point) { - return dot_2d(normal, minus_2d(point, Point{})); - }; - - // Define a function to get the minimum and maximum projected position of the corners - // of a given bounding box along the normal line of the face - auto get_projected_min_max = [&get_position_along_line, &normal](Iter begin, Iter end) { - const auto zero_point = Point{}; - auto min_corners = get_position_along_line(closest_line_point_2d(normal, zero_point, *begin)); - auto max_corners = min_corners; - - for (auto & point = begin; point != end; ++point) { - const auto point_projected = closest_line_point_2d(normal, zero_point, *point); - const auto position_along_line = get_position_along_line(point_projected); - min_corners = std::min(min_corners, position_along_line); - max_corners = std::max(max_corners, position_along_line); - } - return std::pair{min_corners, max_corners}; - }; - - // Perform the actual computations for the extent computation - auto minmax_1 = get_projected_min_max(begin1, end1); - auto minmax_2 = get_projected_min_max(begin2, end2); - - // Check for any intersections - const auto eps = std::numeric_limits::epsilon(); - if (minmax_1.first > minmax_2.second + eps || minmax_2.first > minmax_1.second + eps) { - // Found separating hyperplane, stop - return false; - } - } - - // No separating hyperplane found, boxes collide - return true; -} - -/// \brief Get the intersection between two polygons. The polygons should be provided in an -/// identical format to the output of `convex_hull` function as in the corners should be ordered -/// in a CCW fashion. -/// The computation is done by: -/// * Find the corners of each polygon that are contained by the other polygon. -/// * Find the intersection points between two polygons -/// * Combine these points and order CCW to get the final polygon. -/// The criteria for intersection is better explained in: -/// "Area of intersection of arbitrary polygons" (Livermore, Calif, 1977) -/// See https://www.osti.gov/servlets/purl/7309916/, chapter II - B -/// TODO(yunus.caliskan): This is a naive implementation. We should scan for a more efficient -/// algorithm: #1230 -/// \tparam Iterable1T A container class that has stl style iterators defined. -/// \tparam Iterable2T A container class that has stl style iterators defined. -/// \tparam PointT Point type that have the adapters for the x and y fields. -/// set to `Point1T` -/// \param polygon1 A convex polygon -/// \param polygon2 A convex polygon -/// \return The resulting conv -template < - template class Iterable1T, template class Iterable2T, typename PointT> -std::list convex_polygon_intersection2d( - const Iterable1T & polygon1, const Iterable2T & polygon2) -{ - std::list result; - details::append_contained_points(polygon1, polygon2, result); - details::append_contained_points(polygon2, polygon1, result); - details::append_intersection_points(polygon1, polygon2, result); - const auto end_it = common::geometry::convex_hull(result); - result.resize(static_cast(std::distance(result.cbegin(), end_it))); - return result; -} - -/// \brief Compute the intersection over union of two 2d convex polygons. If any of the polygons -/// span a zero area, the result is 0.0. -/// \tparam Iterable1T A container class that has stl style iterators defined. -/// \tparam Iterable2T A container class that has stl style iterators defined. -/// \tparam Point1T Point type that have the adapters for the x and y fields. -/// \tparam Point2T Point type that have the adapters for the x and y fields. -/// \param polygon1 A convex polygon -/// \param polygon2 A convex polygon -/// \return (Intersection / Union) between two given polygons. -/// \throws std::domain_error If there is any inconsistency on the underlying geometrical -/// computation. -template < - template class Iterable1T, template class Iterable2T, typename PointT> -common::types::float32_t convex_intersection_over_union_2d( - const Iterable1T & polygon1, const Iterable2T & polygon2) -{ - constexpr auto eps = std::numeric_limits::epsilon(); - const auto intersection = convex_polygon_intersection2d(polygon1, polygon2); - - const auto intersection_area = - common::geometry::area_2d(intersection.begin(), intersection.end()); - - if (intersection_area < eps) { - return 0.0F; // There's either no intersection or the points are collinear - } - - const auto polygon1_area = common::geometry::area_2d(polygon1.begin(), polygon1.end()); - const auto polygon2_area = common::geometry::area_2d(polygon2.begin(), polygon2.end()); - - const auto union_area = polygon1_area + polygon2_area - intersection_area; - if (union_area < eps) { - throw std::domain_error("IoU is undefined for polygons with a zero union area"); - } - - return intersection_area / union_area; -} - -} // namespace geometry -} // namespace common -} // namespace autoware - -#endif // AUTOWARE_AUTO_GEOMETRY__INTERSECTION_HPP_ diff --git a/common/autoware_auto_geometry/include/autoware_auto_geometry/interval.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/interval.hpp deleted file mode 100644 index 54be2c32b1d05..0000000000000 --- a/common/autoware_auto_geometry/include/autoware_auto_geometry/interval.hpp +++ /dev/null @@ -1,358 +0,0 @@ -// Copyright 2020 Mapless AI, Inc. -// -// 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. - -#ifndef AUTOWARE_AUTO_GEOMETRY__INTERVAL_HPP_ -#define AUTOWARE_AUTO_GEOMETRY__INTERVAL_HPP_ - -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -namespace autoware -{ -namespace common -{ -namespace geometry -{ - -/** - * @brief Data structure to contain scalar interval bounds. - * - * @post The interval is guaranteed to be valid upon successful construction. An - * interval [min, max] is "valid" if it is empty (min/max = NaN) or its bounds - * are ordered (min <= max). - */ -template -class Interval -{ - static_assert(std::is_floating_point::value, "Intervals only support floating point types."); - -public: - /** - * @brief Compute equality. - * - * Two intervals compare equal iff they are both valid and they are both - * either empty or have equal bounds. - * - * @note This is defined inline because the class is templated. - * - * @return True iff the intervals compare equal. - */ - friend bool operator==(const Interval & i1, const Interval & i2) - { - const auto min_eq = (Interval::min(i1) == Interval::min(i2)); - const auto max_eq = (Interval::max(i1) == Interval::max(i2)); - const auto bounds_equal = (min_eq && max_eq); - const auto both_empty = (Interval::empty(i1) && Interval::empty(i2)); - return both_empty || bounds_equal; - } - - /** - * @brief Compute inequality and the logical negation of equality. - * @note This is defined inline because the class is templated. - */ - friend bool operator!=(const Interval & i1, const Interval & i2) { return !(i1 == i2); } - - /** - * @brief Stream overload for Interval types. - * - * @note Output precision is fixed inside the function definition, and the - * serialization is JSON compatible. - * - * @note The serialization is lossy. It is used for debugging and for - * generating exception strings. - */ - friend std::ostream & operator<<(std::ostream & os, const Interval & i) - { - constexpr auto PRECISION = 5; - - // Internal helper to format the output. - const auto readable_extremum = [](const T & val) { - if (val == std::numeric_limits::lowest()) { - return std::string("REAL_MIN"); - } - if (val == std::numeric_limits::max()) { - return std::string("REAL_MAX"); - } - - std::stringstream ss; - ss.setf(std::ios::fixed, std::ios::floatfield); - ss.precision(PRECISION); - ss << val; - return ss.str(); - }; - - // Do stream output. - if (Interval::empty(i)) { - return os << "{}"; - } - return os << "{\"min\": " << readable_extremum(Interval::min(i)) - << ", \"max\": " << readable_extremum(Interval::max(i)) << "}"; - } - - /** - * @brief Test whether the two intervals have bounds within epsilon of each - * other. - * - * @note If both intervals are empty, this returns true. If only one is empty, - * this returns false. - */ - static bool abs_eq(const Interval & i1, const Interval & i2, const T & eps); - - /** @brief The minimum bound of the interval. */ - static T min(const Interval & i) { return i.min_; } - - /** @brief The maximum bound of the interval. */ - static T max(const Interval & i) { return i.max_; } - - /** - * @brief Return the measure (length) of the interval. - * - * @note For empty or invalid intervals, NaN is returned. See Interval::empty - * for note on distinction between measure zero and the emptiness property. - */ - static T measure(const Interval & i); - - /** - * @brief Utility for checking whether an interval has zero measure. - * - * @note For empty or invalid intervals, false is returned. See - * Interval::empty for note on distinction between measure zero and the - * emptiness property. - * - * @return True iff the interval has zero measure. - */ - static bool zero_measure(const Interval & i); - - /** - * @brief Whether the interval is empty or not. - * - * @note Emptiness refers to whether the interval contains any points and is - * thus a distinct property from measure: an interval is non-empty if contains - * only a single point even though its measure in that case is zero. - * - * @return True iff the interval is empty. - */ - static bool empty(const Interval & i); - - /** - * @brief Test for whether a given interval contains a given value within the given epsilon - * @return True iff 'interval' contains 'value'. - */ - static bool contains( - const Interval & i, const T & value, const T & eps = std::numeric_limits::epsilon()); - - /** - * @brief Test for whether 'i1' subseteq 'i2' - * @return True iff i1 subseteq i2. - */ - static bool is_subset_eq(const Interval & i1, const Interval & i2); - - /** - * @brief Compute the intersection of two intervals as a new interval. - */ - static Interval intersect(const Interval & i1, const Interval & i2); - - /** - * @brief Clamp a scalar 'val' onto 'interval'. - * @return If 'val' in 'interval', return 'val'; otherwise return the nearer - * interval bound. - */ - static T clamp_to(const Interval & i, T val); - - /** - * @brief Constructor: initialize an empty interval with members set to NaN. - */ - Interval(); - - /** - * @brief Constructor: specify exact interval bounds. - * - * @note An empty interval is specified by setting both bounds to NaN. - * @note An exception is thrown if the specified bounds are invalid. - * - * @post Construction is successful iff the interval is valid. - */ - Interval(const T & min, const T & max); - -private: - static constexpr T NaN = std::numeric_limits::quiet_NaN(); - - T min_; - T max_; - - /** - * @brief Verify that the bounds are valid in an interval. - * @note This method is private because it can only be used in the - * constructor. Once an interval has been constructed, its bounds are - * guaranteed to be valid. - */ - static bool bounds_valid(const Interval & i); -}; // class Interval - -//------------------------------------------------------------------------------ - -typedef Interval Interval_d; -typedef Interval Interval_f; - -//------------------------------------------------------------------------------ - -template -constexpr T Interval::NaN; - -//------------------------------------------------------------------------------ - -template -Interval::Interval() : min_(Interval::NaN), max_(Interval::NaN) -{ -} - -//------------------------------------------------------------------------------ - -template -Interval::Interval(const T & min, const T & max) : min_(min), max_(max) -{ - if (!Interval::bounds_valid(*this)) { - std::stringstream ss; - ss << "Attempted to construct an invalid interval: " << *this; - throw std::runtime_error(ss.str()); - } -} - -//------------------------------------------------------------------------------ - -template -bool Interval::abs_eq(const Interval & i1, const Interval & i2, const T & eps) -{ - namespace comp = helper_functions::comparisons; - - const auto both_empty = Interval::empty(i1) && Interval::empty(i2); - const auto both_non_empty = !Interval::empty(i1) && !Interval::empty(i2); - - const auto mins_equal = comp::abs_eq(Interval::min(i1), Interval::min(i2), eps); - const auto maxes_equal = comp::abs_eq(Interval::max(i1), Interval::max(i2), eps); - const auto both_non_empty_equal = both_non_empty && mins_equal && maxes_equal; - - return both_empty || both_non_empty_equal; -} - -//------------------------------------------------------------------------------ - -template -bool Interval::zero_measure(const Interval & i) -{ - // An empty interval will return false because (NaN == NaN) is false. - return Interval::min(i) == Interval::max(i); -} - -//------------------------------------------------------------------------------ - -template -bool Interval::empty(const Interval & i) -{ - return std::isnan(Interval::min(i)) && std::isnan(Interval::max(i)); -} - -//------------------------------------------------------------------------------ - -template -bool Interval::bounds_valid(const Interval & i) -{ - const auto is_ordered = (Interval::min(i) <= Interval::max(i)); - - // Check for emptiness explicitly because it requires both bounds to be NaN - return Interval::empty(i) || is_ordered; -} - -//------------------------------------------------------------------------------ - -template -bool Interval::is_subset_eq(const Interval & i1, const Interval & i2) -{ - const auto lower_contained = (Interval::min(i1) >= Interval::min(i2)); - const auto upper_contained = (Interval::max(i1) <= Interval::max(i2)); - return lower_contained && upper_contained; -} - -//------------------------------------------------------------------------------ - -template -bool Interval::contains(const Interval & i, const T & value, const T & eps) -{ - return common::helper_functions::comparisons::abs_gte(value, Interval::min(i), eps) && - common::helper_functions::comparisons::abs_lte(value, Interval::max(i), eps); -} - -//------------------------------------------------------------------------------ - -template -T Interval::measure(const Interval & i) -{ - return Interval::max(i) - Interval::min(i); -} - -//------------------------------------------------------------------------------ - -template -Interval Interval::intersect(const Interval & i1, const Interval & i2) -{ - // Construct intersection assuming an intersection exists. - try { - const auto either_empty = Interval::empty(i1) || Interval::empty(i2); - const auto min = std::max(Interval::min(i1), Interval::min(i2)); - const auto max = std::min(Interval::max(i1), Interval::max(i2)); - return either_empty ? Interval() : Interval(min, max); - } catch (...) { - } - - // Otherwise, the intersection is empty. - return Interval(); -} - -//------------------------------------------------------------------------------ - -template -T Interval::clamp_to(const Interval & i, T val) -{ - // clamp val to min - val = std::max(val, Interval::min(i)); - - // clamp val to max - val = std::min(val, Interval::max(i)); - - return Interval::empty(i) ? Interval::NaN : val; -} - -//------------------------------------------------------------------------------ - -} // namespace geometry -} // namespace common -} // namespace autoware - -#endif // AUTOWARE_AUTO_GEOMETRY__INTERVAL_HPP_ diff --git a/common/autoware_auto_geometry/include/autoware_auto_geometry/lookup_table.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/lookup_table.hpp deleted file mode 100644 index 7b8867ca096ae..0000000000000 --- a/common/autoware_auto_geometry/include/autoware_auto_geometry/lookup_table.hpp +++ /dev/null @@ -1,179 +0,0 @@ -// Copyright 2017-2020 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. -// -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. - -/// \file -/// \brief This file contains a 1D linear lookup table implementation - -#ifndef AUTOWARE_AUTO_GEOMETRY__LOOKUP_TABLE_HPP_ -#define AUTOWARE_AUTO_GEOMETRY__LOOKUP_TABLE_HPP_ - -#include "autoware_auto_geometry/interval.hpp" - -#include - -#include -#include -#include - -namespace autoware -{ -namespace common -{ -namespace helper_functions -{ - -namespace -{ - -/** - * @brief Compute a scaling between 'a' and 'b' - * @note scaling is clamped to be in the interval [0, 1] - */ -template -T interpolate(const T & a, const T & b, U scaling) -{ - static const geometry::Interval UNIT_INTERVAL(static_cast(0), static_cast(1)); - scaling = geometry::Interval::clamp_to(UNIT_INTERVAL, scaling); - - const auto m = (b - a); - const auto offset = static_cast(m) * scaling; - return a + static_cast(offset); -} - -// TODO(c.ho) support more forms of interpolation as template functor -// Actual lookup logic, assuming all invariants hold: -// Throw if value is not finite -template -T lookup_impl_1d(const std::vector & domain, const std::vector & range, const T value) -{ - if (!std::isfinite(value)) { - throw std::domain_error{"Query value is not finite (NAN or INF)"}; - } - if (value <= domain.front()) { - return range.front(); - } else if (value >= domain.back()) { - return range.back(); - } else { - // Fall through to normal case - } - - auto second_idx{0U}; - for (auto idx = 1U; idx < domain.size(); ++idx) { - if (value < domain[idx]) { - second_idx = idx; - break; - } - } - // T must be a floating point between 0 and 1 - const auto num = static_cast(value - domain[second_idx - 1U]); - const auto den = static_cast(domain[second_idx] - domain[second_idx - 1U]); - const auto t = num / den; - const auto val = interpolate(range[second_idx - 1U], range[second_idx], t); - return static_cast(val); -} - -// Check invariants for table lookup: -template -void check_table_lookup_invariants(const std::vector & domain, const std::vector & range) -{ - if (domain.size() != range.size()) { - throw std::domain_error{"Domain's size does not match range's"}; - } - if (domain.empty()) { - throw std::domain_error{"Empty domain or range"}; - } - // Check if sorted: Can start at 1 because not empty - for (auto idx = 1U; idx < domain.size(); ++idx) { - if (domain[idx] <= domain[idx - 1U]) { // This is safe because indexing starts at 1 - throw std::domain_error{"Domain is not sorted"}; - } - } -} -} // namespace - -/// Do a 1D table lookup: Does some semi-expensive O(N) error checking first. -/// If query value fall out of the domain, then the value at the corresponding edge of the domain is -/// returned. -/// \param[in] domain The domain, or set of x values -/// \param[in] range The range, or set of y values -/// \param[in] value The point in the domain to query, x -/// \return A linearly interpolated value y, corresponding to the query, x -/// \throw std::domain_error If domain or range is empty -/// \throw std::domain_error If range is not the same size as domain -/// \throw std::domain_error If domain is not sorted -/// \throw std::domain_error If value is not finite (NAN or INF) -/// \tparam T The type of the function, must be interpolatable -template -T lookup_1d(const std::vector & domain, const std::vector & range, const T value) -{ - check_table_lookup_invariants(domain, range); - - return lookup_impl_1d(domain, range, value); -} - -/// A class wrapping a 1D lookup table. Intended for more frequent lookups. Error checking is pushed -/// into the constructor and not done in the lookup function call -/// \tparam T The type of the function, must be interpolatable -template -class LookupTable1D -{ -public: - /// Constructor - /// \param[in] domain The domain, or set of x values - /// \param[in] range The range, or set of y values - /// \throw std::domain_error If domain or range is empty - /// \throw std::domain_error If range is not the same size as domain - /// \throw std::domain_error If domain is not sorted - LookupTable1D(const std::vector & domain, const std::vector & range) - : m_domain{domain}, m_range{range} - { - check_table_lookup_invariants(m_domain, m_range); - } - - /// Move constructor - /// \param[in] domain The domain, or set of x values - /// \param[in] range The range, or set of y values - /// \throw std::domain_error If domain or range is empty - /// \throw std::domain_error If range is not the same size as domain - /// \throw std::domain_error If domain is not sorted - LookupTable1D(std::vector && domain, std::vector && range) - : m_domain{domain}, m_range{range} - { - check_table_lookup_invariants(m_domain, m_range); - } - - /// Do a 1D table lookup - /// If query value fall out of the domain, then the value at the corresponding edge of the domain - /// is returned. - /// \param[in] value The point in the domain to query, x - /// \return A linearly interpolated value y, corresponding to the query, x - /// \throw std::domain_error If value is not finite - T lookup(const T value) const { return lookup_impl_1d(m_domain, m_range, value); } - /// Get the domain table - const std::vector & domain() const noexcept { return m_domain; } - /// Get the range table - const std::vector & range() const noexcept { return m_range; } - -private: - std::vector m_domain; - std::vector m_range; -}; // class LookupTable1D - -} // namespace helper_functions -} // namespace common -} // namespace autoware - -#endif // AUTOWARE_AUTO_GEOMETRY__LOOKUP_TABLE_HPP_ diff --git a/common/autoware_auto_geometry/include/autoware_auto_geometry/spatial_hash.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/spatial_hash.hpp deleted file mode 100644 index 8936e2c17d779..0000000000000 --- a/common/autoware_auto_geometry/include/autoware_auto_geometry/spatial_hash.hpp +++ /dev/null @@ -1,332 +0,0 @@ -// Copyright 2019 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. -// -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. -/// \file -/// \brief This file implements a spatial hash for efficient fixed-radius near neighbor queries in -/// 2D - -#ifndef AUTOWARE_AUTO_GEOMETRY__SPATIAL_HASH_HPP_ -#define AUTOWARE_AUTO_GEOMETRY__SPATIAL_HASH_HPP_ - -#include "autoware_auto_geometry/spatial_hash_config.hpp" -#include "autoware_auto_geometry/visibility_control.hpp" - -#include - -#include -#include -#include - -using autoware::common::types::bool8_t; -using autoware::common::types::float32_t; - -namespace autoware -{ -namespace common -{ -namespace geometry -{ -/// \brief All objects related to the spatial hash data structure for efficient near neighbor lookup -namespace spatial_hash -{ - -/// \brief An implementation of the spatial hash or integer lattice data structure for efficient -/// (O(1)) near neighbor queries. -/// \tparam PointT The point type stored in this data structure. Must have float members x, y, and z -/// -/// This implementation can support both 2D and 3D queries -/// (though only one type per data structure), and can support queries of varying radius. This data -/// structure cannot do near neighbor lookups for euclidean distance in arbitrary dimensions. -template -class GEOMETRY_PUBLIC SpatialHashBase -{ - using Index3 = details::Index3; - // lint -e{9131} NOLINT There's no other way to make this work in a static assert - static_assert( - std::is_same::value || std::is_same::value, - "SpatialHash only works with Config2d or Config3d"); - -public: - using Hash = std::unordered_multimap; - using IT = typename Hash::const_iterator; - /// \brief Wrapper around an iterator and a distance (from some query point) - class Output - { - public: - /// \brief Constructor - /// \param[in] iterator An iterator pointing to some point - /// \param[in] distance The euclidean distance (2d or 3d) to a reference point - Output(const IT iterator, const float32_t distance) : m_iterator(iterator), m_distance(distance) - { - } - /// \brief Get stored point - /// \return A const reference to the stored point - const PointT & get_point() const { return m_iterator->second; } - /// \brief Get underlying iterator - /// \return A copy of the underlying iterator - IT get_iterator() const { return m_iterator; } - /// \brief Convert to underlying point - /// \return A reference to the underlying point - operator const PointT &() const { return get_point(); } - /// \brief Convert to underlying iterator - /// \return A copy of the iterator - operator IT() const { return get_iterator(); } - /// \brief Get distance to reference point - /// \return The distance - float32_t get_distance() const { return m_distance; } - - private: - IT m_iterator; - float32_t m_distance; - }; // class Output - using OutputVector = typename std::vector; - - /// \brief Constructor - /// \param[in] cfg The configuration object for this class - explicit SpatialHashBase(const ConfigT & cfg) - : m_config{cfg}, - m_hash(), - m_neighbors{}, // TODO(c.ho) reserve, but there's no default constructor for output - m_bins_hit{}, // zero initialization (and below) - m_neighbors_found{} - { - } - - /// \brief Inserts point - /// \param[in] pt The Point to insert - /// \return Iterator pointing to the inserted point - /// \throw std::length_error If the data structure is at capacity - IT insert(const PointT & pt) - { - if (size() >= capacity()) { - throw std::length_error{"SpatialHash: Cannot insert past capacity"}; - } - return insert_impl(pt); - } - - /// \brief Inserts a range of points - /// \param[in] begin The start of the range of points to insert - /// \param[in] end The end of the range of points to insert - /// \tparam IteratorT The iterator type - /// \throw std::length_error If the range of points to insert exceeds the data structure's - /// capacity - template - void insert(IteratorT begin, IteratorT end) - { - // This check is here for strong exception safety - if ((size() + std::distance(begin, end)) > capacity()) { - throw std::length_error{"SpatialHash: Cannot multi-insert past capacity"}; - } - for (IteratorT it = begin; it != end; ++it) { - (void)insert_impl(*it); - } - } - - /// \brief Removes the specified element from the data structure - /// \param[in] point An iterator pointing to a point to be removed - /// \return An iterator pointing to the element after the erased element - /// \throw std::domain_error If pt is invalid or does not belong to this data structure - /// - /// \note There is no reliable way to check if an iterator is invalid. The checks here are - /// based on a heuristic and is not guaranteed to find all invalid iterators. This method - /// should be used with care and only on valid iterators - IT erase(const IT point) - { - if (end() == m_hash.find(point->first)) { - throw std::domain_error{"SpatialHash: Attempting to erase invalid iterator"}; - } - return m_hash.erase(point); - } - - /// \brief Reset the state of the data structure - void clear() { m_hash.clear(); } - /// \brief Get current number of element stored in this data structure - /// \return Number of stored elements - Index size() const { return m_hash.size(); } - /// \brief Get the maximum capacity of the data structure - /// \return The capacity of the data structure - Index capacity() const { return m_config.get_capacity(); } - /// \brief Whether the hash is empty - /// \return True if data structure is empty - bool8_t empty() const { return m_hash.empty(); } - /// \brief Get iterator to beginning of data structure - /// \return Iterator - IT begin() const { return m_hash.begin(); } - /// \brief Get iterator to end of data structure - /// \return Iterator - IT end() const { return m_hash.end(); } - /// \brief Get iterator to beginning of data structure - /// \return Iterator - IT cbegin() const { return begin(); } - /// \brief Get iterator to end of data structure - /// \return Iterator - IT cend() const { return end(); } - - /// \brief Get the number of bins touched during the lifetime of this object, for debugging and - /// size tuning - /// \return The total number of bins touched during near() queries - Index bins_hit() const { return m_bins_hit; } - - /// \brief Get number of near neighbors found during the lifetime of this object, for debugging - /// and size tuning - /// \return The total number of neighbors found during near() queries - Index neighbors_found() const { return m_neighbors_found; } - -protected: - /// \brief Finds all points within a fixed radius of a reference point - /// \param[in] x The x component of the reference point - /// \param[in] y The y component of the reference point - /// \param[in] z The z component of the reference point, respected only if the spatial hash is not - /// 2D. - /// \param[in] radius The radius within which to find all near points - /// \return A const reference to a vector containing iterators pointing to - /// all points within the radius, and the actual distance to the reference point - const OutputVector & near_impl( - const float32_t x, const float32_t y, const float32_t z, const float32_t radius) - { - // reset output - m_neighbors.clear(); - // Compute bin, bin range - const Index3 ref_idx = m_config.index3(x, y, z); - const float32_t radius2 = radius * radius; - const details::BinRange idx_range = m_config.bin_range(ref_idx, radius); - Index3 idx = idx_range.first; - // For bins in radius - do { // guaranteed to have at least the bin ref_idx is in - // update book-keeping - ++m_bins_hit; - // Iterating in a square/cube pattern is easier than constructing sphere pattern - if (m_config.is_candidate_bin(ref_idx, idx, radius2)) { - // For point in bin - const Index jdx = m_config.index(idx); - const auto range = m_hash.equal_range(jdx); - for (auto it = range.first; it != range.second; ++it) { - const auto & pt = it->second; - const float32_t dist2 = m_config.distance_squared(x, y, z, pt); - if (dist2 <= radius2) { - // Only compute true distance if necessary - m_neighbors.emplace_back(it, sqrtf(dist2)); - } - } - } - } while (m_config.next_bin(idx_range, idx)); - // update book-keeping - m_neighbors_found += m_neighbors.size(); - return m_neighbors; - } - -private: - /// \brief Internal insert method with no error checking - /// \param[in] pt The Point to insert - GEOMETRY_LOCAL IT insert_impl(const PointT & pt) - { - // Compute bin - const Index idx = - m_config.bin(point_adapter::x_(pt), point_adapter::y_(pt), point_adapter::z_(pt)); - // Insert into bin - return m_hash.insert(std::make_pair(idx, pt)); - } - - const ConfigT m_config; - Hash m_hash; - OutputVector m_neighbors; - Index m_bins_hit; - Index m_neighbors_found; -}; // class SpatialHashBase - -/// \brief The class to be used for specializing on -/// apex_app::common::geometry::spatial_hash::SpatialHashBase to provide different function -/// signatures on 2D and 3D configurations -/// \tparam PointT The point type stored in this data structure. Must have float members x, y and z -template -class GEOMETRY_PUBLIC SpatialHash; - -/// \brief Explicit specialization of SpatialHash for 2D configuration -/// \tparam PointT The point type stored in this data structure. -template -class GEOMETRY_PUBLIC SpatialHash : public SpatialHashBase -{ -public: - using OutputVector = typename SpatialHashBase::OutputVector; - - explicit SpatialHash(const Config2d & cfg) : SpatialHashBase(cfg) {} - - /// \brief Finds all points within a fixed radius of a reference point - /// \param[in] x The x component of the reference point - /// \param[in] y The y component of the reference point - /// \param[in] radius The radius within which to find all near points - /// \return A const reference to a vector containing iterators pointing to - /// all points within the radius, and the actual distance to the reference point - const OutputVector & near(const float32_t x, const float32_t y, const float32_t radius) - { - return this->near_impl(x, y, 0.0F, radius); - } - - /// \brief Finds all points within a fixed radius of a reference point - /// \param[in] pt The reference point. Only the x and y members are respected. - /// \param[in] radius The radius within which to find all near points - /// \return A const reference to a vector containing iterators pointing to - /// all points within the radius, and the actual distance to the reference point - const OutputVector & near(const PointT & pt, const float32_t radius) - { - return near(point_adapter::x_(pt), point_adapter::y_(pt), radius); - } -}; - -/// \brief Explicit specialization of SpatialHash for 3D configuration -/// \tparam PointT The point type stored in this data structure. Must have float members x, y and z -template -class GEOMETRY_PUBLIC SpatialHash : public SpatialHashBase -{ -public: - using OutputVector = typename SpatialHashBase::OutputVector; - - explicit SpatialHash(const Config3d & cfg) : SpatialHashBase(cfg) {} - - /// \brief Finds all points within a fixed radius of a reference point - /// \param[in] x The x component of the reference point - /// \param[in] y The y component of the reference point - /// \param[in] z The z component of the reference point, respected only if the spatial hash is not - /// 2D. - /// \param[in] radius The radius within which to find all near points - /// \return A const reference to a vector containing iterators pointing to - /// all points within the radius, and the actual distance to the reference point - const OutputVector & near( - const float32_t x, const float32_t y, const float32_t z, const float32_t radius) - { - return this->near_impl(x, y, z, radius); - } - - /// \brief Finds all points within a fixed radius of a reference point - /// \param[in] pt The reference point. - /// \param[in] radius The radius within which to find all near points - /// \return A const reference to a vector containing iterators pointing to - /// all points within the radius, and the actual distance to the reference point - const OutputVector & near(const PointT & pt, const float32_t radius) - { - return near(point_adapter::x_(pt), point_adapter::y_(pt), point_adapter::z_(pt), radius); - } -}; - -template -using SpatialHash2d = SpatialHash; -template -using SpatialHash3d = SpatialHash; -} // namespace spatial_hash -} // namespace geometry -} // namespace common -} // namespace autoware - -#endif // AUTOWARE_AUTO_GEOMETRY__SPATIAL_HASH_HPP_ diff --git a/common/autoware_auto_geometry/include/autoware_auto_geometry/spatial_hash_config.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/spatial_hash_config.hpp deleted file mode 100644 index 24c4d6e879d4a..0000000000000 --- a/common/autoware_auto_geometry/include/autoware_auto_geometry/spatial_hash_config.hpp +++ /dev/null @@ -1,450 +0,0 @@ -// Copyright 2019 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. -// -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. -/// \file -/// \brief This file implements a spatial hash for efficient fixed-radius near neighbor queries in -/// 2D - -#ifndef AUTOWARE_AUTO_GEOMETRY__SPATIAL_HASH_CONFIG_HPP_ -#define AUTOWARE_AUTO_GEOMETRY__SPATIAL_HASH_CONFIG_HPP_ - -#include "autoware_auto_geometry/common_2d.hpp" -#include "autoware_auto_geometry/visibility_control.hpp" - -#include -#include - -#include -#include -#include -#include -#include - -using autoware::common::types::bool8_t; -using autoware::common::types::float32_t; -using autoware::common::types::float64_t; - -namespace autoware -{ -namespace common -{ -namespace geometry -{ -/// \brief All objects related to the spatial hash data structure for efficient near neighbor lookup -namespace spatial_hash -{ -/// \brief Index type for identifying bins of the hash/lattice -using Index = std::size_t; -/// \brief Spatial hash functionality not intended to be used by an external user -namespace details -{ -/// \brief Internal struct for packing three indices together -/// -/// The use of this struct publicly is a violation of our coding standards, but I claim it's -/// fine because (a) it's details, (b) it is literally three unrelated members packaged together. -/// This type is needed for conceptual convenience so I don't have massive function parameter -/// lists -struct GEOMETRY_PUBLIC Index3 -{ - Index x; - Index y; - Index z; -}; // struct Index3 - -using BinRange = std::pair; -} // namespace details - -/// \brief The base class for the configuration object for the SpatialHash class -/// \tparam Derived The type of the derived class to support static polymorphism/CRTP -template -class GEOMETRY_PUBLIC Config : public autoware::common::helper_functions::crtp -{ -public: - /// \brief Constructor for spatial hash - /// \param[in] min_x The minimum x value for the spatial hash - /// \param[in] max_x The maximum x value for the spatial hash - /// \param[in] min_y The minimum y value for the spatial hash - /// \param[in] max_y The maximum y value for the spatial hash - /// \param[in] min_z The minimum z value for the spatial hash - /// \param[in] max_z The maximum z value for the spatial hash - /// \param[in] radius The look up radius - /// \param[in] capacity The maximum number of points the spatial hash can store - Config( - const float32_t min_x, const float32_t max_x, const float32_t min_y, const float32_t max_y, - const float32_t min_z, const float32_t max_z, const float32_t radius, const Index capacity) - : m_min_x{min_x}, - m_min_y{min_y}, - m_min_z{min_z}, - m_max_x{max_x}, - m_max_y{max_y}, - m_max_z{max_z}, - m_side_length{radius}, - m_side_length2{radius * radius}, - m_side_length_inv{1.0F / radius}, - m_capacity{capacity}, - m_max_x_idx{check_basis_direction(min_x, max_x)}, - m_max_y_idx{check_basis_direction(min_y, max_y)}, - m_max_z_idx{check_basis_direction(min_z, max_z)}, - m_y_stride{m_max_x_idx + 1U}, - m_z_stride{m_y_stride * (m_max_y_idx + 1U)} - { - if (radius <= 0.0F) { - throw std::domain_error("Error constructing SpatialHash: must have positive side length"); - } - - if ((m_max_y_idx + m_y_stride) > std::numeric_limits::max() / 2U) { - // TODO(c.ho) properly check for multiplication overflow - throw std::domain_error("SpatialHash::Config: voxel index may overflow!"); - } - // small fudging to prevent weird boundary effects - // (e.g (x=x_max, y) rolls index over to (x=0, y+1) - // cspell: ignore FEPS - // FEPS means "Float EPSilon" - constexpr auto FEPS = std::numeric_limits::epsilon(); - // lint -e{1938} read only access is fine NOLINT - m_max_x -= FEPS; - m_max_y -= FEPS; - m_max_z -= FEPS; - if ((m_z_stride + m_max_z_idx) > std::numeric_limits::max() / 2U) { - // TODO(c.ho) properly check for multiplication overflow - throw std::domain_error("SpatialHash::Config: voxel index may overflow!"); - } - // I don't know if this is even possible given other checks - if (std::numeric_limits::max() == m_max_z_idx) { - throw std::domain_error("SpatialHash::Config: max z index exceeds reasonable value"); - } - } - - /// \brief Given a reference index triple, compute the first and last bin - /// \param[in] ref The reference index triple - /// \param[in] radius The allowable radius for any point in the reference bin to any point in the - /// range - /// \return A pair where the first element is an index triple of the first bin, and the second - /// element is an index triple for the last bin - details::BinRange bin_range(const details::Index3 & ref, const float radius) const - { - // Compute distance in units of voxels - const Index i_radius = static_cast(std::ceil(radius / m_side_length)); - // Dumb ternary because potentially unsigned Index type - const Index x_min = (ref.x > i_radius) ? (ref.x - i_radius) : 0U; - const Index y_min = (ref.y > i_radius) ? (ref.y - i_radius) : 0U; - const Index z_min = (ref.z > i_radius) ? (ref.z - i_radius) : 0U; - // In 2D mode, m_max_z should be 0, same with ref.z - const Index x_max = std::min(ref.x + i_radius, m_max_x_idx); - const Index y_max = std::min(ref.y + i_radius, m_max_y_idx); - const Index z_max = std::min(ref.z + i_radius, m_max_z_idx); - // return bottom-left portion of cube and top-right portion of cube - return {{x_min, y_min, z_min}, {x_max, y_max, z_max}}; - } - - /// \brief Get next index within a given range - /// \return True if idx is valid and still in range - /// \param[in] range The max and min bin indices - /// \param[inout] idx The index to be incremented, updated even if a negative result occurs - bool8_t next_bin(const details::BinRange & range, details::Index3 & idx) const - { - // TODO(c.ho) is there any way to make this neater without triple nested if? - bool8_t ret = true; - ++idx.x; - if (idx.x > range.second.x) { - idx.x = range.first.x; - ++idx.y; - if (idx.y > range.second.y) { - idx.y = range.first.y; - ++idx.z; - if (idx.z > range.second.z) { - ret = false; - } - } - } - return ret; - } - /// \brief Get the maximum capacity of the spatial hash - /// \return The capacity - Index get_capacity() const { return m_capacity; } - - /// \brief Getter for the side length, equivalently the lookup radius - float32_t radius2() const { return m_side_length2; } - - //////////////////////////////////////////////////////////////////////////////////////////// - // "Polymorphic" API - /// \brief Compute the single index given a point - /// \param[in] x The x component of the point - /// \param[in] y The y component of the point - /// \param[in] z The z component of the point - /// \return The combined index of the bin for a given point - Index bin(const float32_t x, const float32_t y, const float32_t z) const - { - return this->impl().bin_(x, y, z); - } - /// \brief Compute whether the query bin and reference bin could possibly contain a pair of points - /// such that their distance is within a certain threshold - /// \param[in] ref The index triple of the bin containing the reference point - /// \param[in] query The index triple of the bin being queried - /// \param[in] ref_distance2 The squared threshold distance - /// \return True if query and ref could possibly hold points within reference distance to one - /// another - bool is_candidate_bin( - const details::Index3 & ref, const details::Index3 & query, const float ref_distance2) const - { - return this->impl().valid(ref, query, ref_distance2); - } - /// \brief Compute the decomposed index given a point - /// \param[in] x The x component of the point - /// \param[in] y The y component of the point - /// \param[in] z The z component of the point - /// \return The decomposed index triple of the bin for the given point - details::Index3 index3(const float32_t x, const float32_t y, const float32_t z) const - { - return this->impl().index3_(x, y, z); - } - /// \brief Compute the composed single index given a decomposed index - /// \param[in] idx A decomposed index triple for a bin - /// \return The composed bin index - Index index(const details::Index3 & idx) const { return this->impl().index_(idx); } - /// \brief Compute the squared distance between the two points - /// \tparam PointT A point type with float members x, y and z, or point adapters defined - /// \param[in] x The x component of the first point - /// \param[in] y The y component of the first point - /// \param[in] z The z component of the first point - /// \param[in] pt The other point being compared - /// \return The squared distance between the points (2d or 3d) - template - float32_t distance_squared( - const float32_t x, const float32_t y, const float32_t z, const PointT & pt) const - { - return this->impl().distance_squared_(x, y, z, pt); - } - -protected: - /// \brief Computes the index in the x basis direction - /// \param[in] x The x value of a point - /// \return The x offset of the index - Index x_index(const float32_t x) const - { - return static_cast( - std::floor((std::min(std::max(x, m_min_x), m_max_x) - m_min_x) * m_side_length_inv)); - } - /// \brief Computes the index in the y basis direction - /// \param[in] y The y value of a point - /// \return The x offset of the index - Index y_index(const float32_t y) const - { - return static_cast( - std::floor((std::min(std::max(y, m_min_y), m_max_y) - m_min_y) * m_side_length_inv)); - } - /// \brief Computes the index in the z basis direction - /// \param[in] z The z value of a point - /// \return The x offset of the index - Index z_index(const float32_t z) const - { - return static_cast( - std::floor((std::min(std::max(z, m_min_z), m_max_z) - m_min_z) * m_side_length_inv)); - } - /// \brief Compose the provided index offsets - Index bin_impl(const Index xdx, const Index ydx) const { return xdx + (ydx * m_y_stride); } - /// \brief Compose the provided index offsets - Index bin_impl(const Index xdx, const Index ydx, const Index zdx) const - { - return bin_impl(xdx, ydx) + (zdx * m_z_stride); - } - - /// \brief The index offset of a point given it's x and y values - /// \param[in] x The x value of a point - /// \param[in] y the y value of a point - /// \return The index of the point in the 2D case, or the offset within a z-slice of the hash - Index bin_impl(const float32_t x, const float32_t y) const - { - return bin_impl(x_index(x), y_index(y)); - } - /// \brief The index of a point given it's x, y and z values - /// \param[in] x The x value of a point - /// \param[in] y the y value of a point - /// \param[in] z the z value of a point - /// \return The index of the bin for the specified point - Index bin_impl(const float32_t x, const float32_t y, const float32_t z) const - { - return bin_impl(x, y) + (z_index(z) * m_z_stride); - } - /// \brief The distance between two indices as a float, where adjacent indices have zero - /// distance (e.g. dist(0, 1) = 0) - float32_t idx_distance(const Index ref_idx, const Index query_idx) const - { - /// Not using fabs because Index is (possibly) unsigned - const Index i_dist = (ref_idx >= query_idx) ? (ref_idx - query_idx) : (query_idx - ref_idx); - float32_t dist = static_cast(i_dist) - 1.0F; - return std::max(dist, 0.0F); - } - - /// \brief Get side length squared - float side_length2() const { return m_side_length2; } - -private: - /// \brief Sanity check a range in a basis direction - /// \return The number of voxels in the given basis direction - Index check_basis_direction(const float32_t min, const float32_t max) const - { - if (min >= max) { - throw std::domain_error("SpatialHash::Config: must have min < max"); - } - // This family of checks is to ensure that you don't get weird casting effects due to huge - // floating point values - const float64_t dmax = static_cast(max); - const float64_t dmin = static_cast(min); - const float64_t width = (dmax - dmin) * static_cast(m_side_length_inv); - constexpr float64_t flt_max = static_cast(std::numeric_limits::max()); - if (flt_max <= width) { - throw std::domain_error("SpatialHash::Config: voxel size approaching floating point limit"); - } - return static_cast(width); - } - float32_t m_min_x; - float32_t m_min_y; - float32_t m_min_z; - float32_t m_max_x; - float32_t m_max_y; - float32_t m_max_z; - float32_t m_side_length; - float32_t m_side_length2; - float32_t m_side_length_inv; - Index m_capacity; - Index m_max_x_idx; - Index m_max_y_idx; - Index m_max_z_idx; - Index m_y_stride; - Index m_z_stride; -}; // class Config - -/// \brief Configuration class for a 2d spatial hash -class GEOMETRY_PUBLIC Config2d : public Config -{ -public: - /// \brief Config constructor for 2D spatial hash - /// \param[in] min_x The minimum x value for the spatial hash - /// \param[in] max_x The maximum x value for the spatial hash - /// \param[in] min_y The minimum y value for the spatial hash - /// \param[in] max_y The maximum y value for the spatial hash - /// \param[in] radius The lookup distance - /// \param[in] capacity The maximum number of points the spatial hash can store - Config2d( - const float32_t min_x, const float32_t max_x, const float32_t min_y, const float32_t max_y, - const float32_t radius, const Index capacity); - /// \brief The index of a point given it's x, y and z values, 2d implementation - /// \param[in] x The x value of a point - /// \param[in] y the y value of a point - /// \param[in] z the z value of a point - /// \return The index of the bin for the specified point - Index bin_(const float32_t x, const float32_t y, const float32_t z) const; - /// \brief Determine if a bin could possibly hold a point within a distance to any point in a - /// reference bin for the 2D case - /// \param[in] ref The decomposed index triple of the reference bin - /// \param[in] query The decomposed index triple of the bin being queried - /// \param[in] ref_distance2 The squared threshold distance - /// \return True if the reference bin and query bin could possibly hold a point within the - /// reference distance - bool valid( - const details::Index3 & ref, const details::Index3 & query, const float ref_distance2) const; - /// \brief Compute the decomposed index given a point, 2d implementation - /// \param[in] x The x component of the point - /// \param[in] y The y component of the point - /// \param[in] z The z component of the point - /// \return The decomposed index triple of the bin for the given point - details::Index3 index3_(const float32_t x, const float32_t y, const float32_t z) const; - /// \brief Compute the composed single index given a decomposed index, 2d implementation - /// \param[in] idx A decomposed index triple for a bin - /// \return The composed bin index - Index index_(const details::Index3 & idx) const; - /// \brief Compute the squared distance between the two points, 2d implementation - /// \tparam PointT A point type with float members x, y and z, or point adapters defined - /// \param[in] x The x component of the first point - /// \param[in] y The y component of the first point - /// \param[in] z The z component of the first point - /// \param[in] pt The other point being compared - /// \return The squared distance between the points (2d) - template - float32_t distance_squared_( - const float32_t x, const float32_t y, const float32_t z, const PointT & pt) const - { - (void)z; - const float32_t dx = x - point_adapter::x_(pt); - const float32_t dy = y - point_adapter::y_(pt); - return (dx * dx) + (dy * dy); - } -}; // class Config2d - -/// \brief Configuration class for a 3d spatial hash -class GEOMETRY_PUBLIC Config3d : public Config -{ -public: - /// \brief Config constructor for a 3d spatial hash - /// \param[in] min_x The minimum x value for the spatial hash - /// \param[in] max_x The maximum x value for the spatial hash - /// \param[in] min_y The minimum y value for the spatial hash - /// \param[in] max_y The maximum y value for the spatial hash - /// \param[in] min_z The minimum z value for the spatial hash - /// \param[in] max_z The maximum z value for the spatial hash - /// \param[in] radius The lookup distance - /// \param[in] capacity The maximum number of points the spatial hash can store - Config3d( - const float32_t min_x, const float32_t max_x, const float32_t min_y, const float32_t max_y, - const float32_t min_z, const float32_t max_z, const float32_t radius, const Index capacity); - /// \brief The index of a point given it's x, y and z values, 3d implementation - /// \param[in] x The x value of a point - /// \param[in] y the y value of a point - /// \param[in] z the z value of a point - /// \return The index of the bin for the specified point - Index bin_(const float32_t x, const float32_t y, const float32_t z) const; - /// \brief Determine if a bin could possibly hold a point within a distance to any point in a - /// reference bin for the 3D case - /// \param[in] ref The decomposed index triple of the reference bin - /// \param[in] query The decomposed index triple of the bin being queried - /// \param[in] ref_distance2 The squared threshold distance - /// \return True if the reference bin and query bin could possibly hold a point within the - /// reference distance - bool valid( - const details::Index3 & ref, const details::Index3 & query, const float ref_distance2) const; - /// \brief Compute the decomposed index given a point, 3d implementation - /// \param[in] x The x component of the point - /// \param[in] y The y component of the point - /// \param[in] z The z component of the point - /// \return The decomposed index triple of the bin for the given point - details::Index3 index3_(const float32_t x, const float32_t y, const float32_t z) const; - /// \brief Compute the composed single index given a decomposed index, 3d implementation - /// \param[in] idx A decomposed index triple for a bin - /// \return The composed bin index - Index index_(const details::Index3 & idx) const; - /// \brief Compute the squared distance between the two points, 3d implementation - /// \tparam PointT A point type with float members x, y and z, or point adapters defined - /// \param[in] x The x component of the first point - /// \param[in] y The y component of the first point - /// \param[in] z The z component of the first point - /// \param[in] pt The other point being compared - /// \return The squared distance between the points (3d) - template - float32_t distance_squared_( - const float32_t x, const float32_t y, const float32_t z, const PointT & pt) const - { - const float32_t dx = x - point_adapter::x_(pt); - const float32_t dy = y - point_adapter::y_(pt); - const float32_t dz = z - point_adapter::z_(pt); - return (dx * dx) + (dy * dy) + (dz * dz); - } -}; // class Config3d -} // namespace spatial_hash -} // namespace geometry -} // namespace common -} // namespace autoware - -#endif // AUTOWARE_AUTO_GEOMETRY__SPATIAL_HASH_CONFIG_HPP_ diff --git a/common/autoware_auto_geometry/include/autoware_auto_geometry/visibility_control.hpp b/common/autoware_auto_geometry/include/autoware_auto_geometry/visibility_control.hpp deleted file mode 100644 index 8972246997997..0000000000000 --- a/common/autoware_auto_geometry/include/autoware_auto_geometry/visibility_control.hpp +++ /dev/null @@ -1,41 +0,0 @@ -// Copyright 2017-2019 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. -// -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. - -#ifndef AUTOWARE_AUTO_GEOMETRY__VISIBILITY_CONTROL_HPP_ -#define AUTOWARE_AUTO_GEOMETRY__VISIBILITY_CONTROL_HPP_ - -//////////////////////////////////////////////////////////////////////////////// -#if defined(__WIN32) -#if defined(GEOMETRY_BUILDING_DLL) || defined(GEOMETRY_EXPORTS) -#define GEOMETRY_PUBLIC __declspec(dllexport) -#define GEOMETRY_LOCAL -#else // defined(GEOMETRY_BUILDING_DLL) || defined(GEOMETRY_EXPORTS) -#define GEOMETRY_PUBLIC __declspec(dllimport) -#define GEOMETRY_LOCAL -#endif // defined(GEOMETRY_BUILDING_DLL) || defined(GEOMETRY_EXPORTS) -#elif defined(__linux__) -#define GEOMETRY_PUBLIC __attribute__((visibility("default"))) -#define GEOMETRY_LOCAL __attribute__((visibility("hidden"))) -#elif defined(__APPLE__) -#define GEOMETRY_PUBLIC __attribute__((visibility("default"))) -#define GEOMETRY_LOCAL __attribute__((visibility("hidden"))) -#elif defined(QNX) -#define GEOMETRY_PUBLIC __attribute__((visibility("default"))) -#define GEOMETRY_LOCAL __attribute__((visibility("hidden"))) -#else // defined(__linux__) -#error "Unsupported Build Configuration" -#endif // defined(__WIN32) -#endif // AUTOWARE_AUTO_GEOMETRY__VISIBILITY_CONTROL_HPP_ diff --git a/common/autoware_auto_geometry/package.xml b/common/autoware_auto_geometry/package.xml deleted file mode 100644 index f53412298a485..0000000000000 --- a/common/autoware_auto_geometry/package.xml +++ /dev/null @@ -1,30 +0,0 @@ - - - - autoware_auto_geometry - 1.0.0 - Geometry related algorithms - Satoshi Ota - Apache License 2.0 - - Apex.AI, Inc. - - ament_cmake_auto - autoware_cmake - - autoware_auto_common - autoware_auto_geometry_msgs - autoware_auto_planning_msgs - autoware_auto_tf2 - autoware_auto_vehicle_msgs - geometry_msgs - - ament_cmake_ros - ament_lint_auto - autoware_lint_common - osrf_testing_tools_cpp - - - ament_cmake - - diff --git a/common/autoware_auto_geometry/src/bounding_box.cpp b/common/autoware_auto_geometry/src/bounding_box.cpp deleted file mode 100644 index 3a4ea96a151a2..0000000000000 --- a/common/autoware_auto_geometry/src/bounding_box.cpp +++ /dev/null @@ -1,157 +0,0 @@ -// Copyright 2017-2019 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. -// -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. - -#include "autoware_auto_geometry/bounding_box/bounding_box_common.hpp" -#include "autoware_auto_geometry/bounding_box/eigenbox_2d.hpp" - -#include -// cspell: ignore eigenbox -#include "autoware_auto_geometry/bounding_box/lfit.hpp" -// cspell: ignore lfit -#include "autoware_auto_geometry/bounding_box/rotating_calipers.hpp" - -#include - -#include -#include -#include -#include -#include - -namespace autoware -{ -namespace common -{ -namespace geometry -{ -namespace bounding_box -{ -namespace details -{ -//////////////////////////////////////////////////////////////////////////////// -void size_2d(const decltype(BoundingBox::corners) & corners, geometry_msgs::msg::Point32 & ret) -{ - ret.x = std::max( - norm_2d(minus_2d(corners[1U], corners[0U])), std::numeric_limits::epsilon()); - ret.y = std::max( - norm_2d(minus_2d(corners[2U], corners[1U])), std::numeric_limits::epsilon()); -} -//////////////////////////////////////////////////////////////////////////////// -void finalize_box(const decltype(BoundingBox::corners) & corners, BoundingBox & box) -{ - (void)std::copy(&corners[0U], &corners[corners.size()], &box.corners[0U]); - // orientation: this is robust to lines - const float32_t yaw_rad_2 = - atan2f(box.corners[2U].y - box.corners[1U].y, box.corners[2U].x - box.corners[1U].x) * 0.5F; - box.orientation.w = cosf(yaw_rad_2); - box.orientation.z = sinf(yaw_rad_2); - // centroid - box.centroid = times_2d(plus_2d(corners[0U], corners[2U]), 0.5F); -} - -autoware_auto_perception_msgs::msg::Shape make_shape(const BoundingBox & box) -{ - autoware_auto_perception_msgs::msg::Shape retval; - // Polygon is 2D rectangle - geometry_msgs::msg::Polygon polygon; - auto & points = polygon.points; - points.resize(4); - - // Note that the x and y of size field in BoundingBox should be swapped when being used to - // compute corners. - // origin of reference system: centroid of bbox - points[0].x = -0.5F * box.size.y; - points[0].y = -0.5F * box.size.x; - points[0].z = -box.size.z; - - points[1] = points[0]; - points[1].y += box.size.x; - - points[2] = points[1]; - points[2].x += box.size.y; - - points[3] = points[2]; - points[3].y -= box.size.x; - - retval.footprint = polygon; - retval.dimensions.z = 2 * box.size.z; - - return retval; -} - -autoware_auto_perception_msgs::msg::DetectedObject make_detected_object(const BoundingBox & box) -{ - autoware_auto_perception_msgs::msg::DetectedObject ret; - - ret.kinematics.pose_with_covariance.pose.position.x = static_cast(box.centroid.x); - ret.kinematics.pose_with_covariance.pose.position.y = static_cast(box.centroid.y); - ret.kinematics.pose_with_covariance.pose.position.z = static_cast(box.centroid.z); - ret.kinematics.pose_with_covariance.pose.orientation.x = static_cast(box.orientation.x); - ret.kinematics.pose_with_covariance.pose.orientation.y = static_cast(box.orientation.y); - ret.kinematics.pose_with_covariance.pose.orientation.z = static_cast(box.orientation.z); - ret.kinematics.pose_with_covariance.pose.orientation.w = static_cast(box.orientation.w); - ret.kinematics.orientation_availability = - autoware_auto_perception_msgs::msg::DetectedObjectKinematics::SIGN_UNKNOWN; - - ret.shape = make_shape(box); - - ret.existence_probability = 1.0F; - - autoware_auto_perception_msgs::msg::ObjectClassification label; - label.label = autoware_auto_perception_msgs::msg::ObjectClassification::UNKNOWN; - label.probability = 1.0F; - ret.classification.emplace_back(std::move(label)); - - return ret; -} - -std::vector GEOMETRY_PUBLIC get_transformed_corners( - const autoware_auto_perception_msgs::msg::Shape & shape_msg, - const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation) -{ - std::vector retval(shape_msg.footprint.points.size()); - geometry_msgs::msg::TransformStamped tf; - tf.transform.rotation = orientation; - tf.transform.translation.x = centroid.x; - tf.transform.translation.y = centroid.y; - tf.transform.translation.z = centroid.z; - - for (size_t i = 0U; i < shape_msg.footprint.points.size(); ++i) { - tf2::doTransform(shape_msg.footprint.points[i], retval[i], tf); - } - return retval; -} - -} // namespace details -/////////////////////////////////////////////////////////////////////////////// -// pre-compilation -using autoware::common::types::PointXYZIF; -template BoundingBox minimum_area_bounding_box(std::list & list); -template BoundingBox minimum_perimeter_bounding_box(std::list & list); -using PointXYZIFVIT = std::vector::iterator; -template BoundingBox eigenbox_2d(const PointXYZIFVIT begin, const PointXYZIFVIT end); -template BoundingBox lfit_bounding_box_2d( - const PointXYZIFVIT begin, const PointXYZIFVIT end); -using geometry_msgs::msg::Point32; -template BoundingBox minimum_area_bounding_box(std::list & list); -template BoundingBox minimum_perimeter_bounding_box(std::list & list); -using Point32VIT = std::vector::iterator; -template BoundingBox eigenbox_2d(const Point32VIT begin, const Point32VIT end); -template BoundingBox lfit_bounding_box_2d(const Point32VIT begin, const Point32VIT end); -} // namespace bounding_box -} // namespace geometry -} // namespace common -} // namespace autoware diff --git a/common/autoware_auto_geometry/src/spatial_hash.cpp b/common/autoware_auto_geometry/src/spatial_hash.cpp deleted file mode 100644 index ffd91aaa08b3a..0000000000000 --- a/common/autoware_auto_geometry/src/spatial_hash.cpp +++ /dev/null @@ -1,104 +0,0 @@ -// Copyright 2019 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. -// -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. - -#include "autoware_auto_geometry/spatial_hash.hpp" - -#include -// lint -e537 NOLINT repeated include file due to cpplint rule -#include -// lint -e537 NOLINT repeated include file due to cpplint rule -#include - -namespace autoware -{ -namespace common -{ -namespace geometry -{ -namespace spatial_hash -{ -//////////////////////////////////////////////////////////////////////////////// -Config2d::Config2d( - const float32_t min_x, const float32_t max_x, const float32_t min_y, const float32_t max_y, - const float32_t radius, const Index capacity) -: Config(min_x, max_x, min_y, max_y, {}, std::numeric_limits::min(), radius, capacity) -{ -} -//////////////////////////////////////////////////////////////////////////////// -Index Config2d::bin_(const float32_t x, const float32_t y, const float32_t z) const -{ - (void)z; - return bin_impl(x, y); -} -//////////////////////////////////////////////////////////////////////////////// -bool Config2d::valid( - const details::Index3 & ref, const details::Index3 & query, const float ref_distance2) const -{ - const float dx = idx_distance(ref.x, query.x); - const float dy = idx_distance(ref.y, query.y); - // minor algebraic manipulation happening below - return (((dx * dx) + (dy * dy)) * side_length2()) <= ref_distance2; -} -//////////////////////////////////////////////////////////////////////////////// -details::Index3 Config2d::index3_(const float32_t x, const float32_t y, const float32_t z) const -{ - (void)z; - return {x_index(x), y_index(y), Index{}}; // zero initialization -} -//////////////////////////////////////////////////////////////////////////////// -Index Config2d::index_(const details::Index3 & idx) const -{ - return bin_impl(idx.x, idx.y); -} -//////////////////////////////////////////////////////////////////////////////// -Config3d::Config3d( - const float32_t min_x, const float32_t max_x, const float32_t min_y, const float32_t max_y, - const float32_t min_z, const float32_t max_z, const float32_t radius, const Index capacity) -: Config(min_x, max_x, min_y, max_y, min_z, max_z, radius, capacity) -{ -} -//////////////////////////////////////////////////////////////////////////////// -Index Config3d::bin_(const float32_t x, const float32_t y, const float32_t z) const -{ - return bin_impl(x, y, z); -} -//////////////////////////////////////////////////////////////////////////////// -bool Config3d::valid( - const details::Index3 & ref, const details::Index3 & query, const float ref_distance2) const -{ - const float dx = idx_distance(ref.x, query.x); - const float dy = idx_distance(ref.y, query.y); - const float dz = idx_distance(ref.z, query.z); - // minor algebraic manipulation happening below - return (((dx * dx) + (dy * dy) + (dz * dz)) * side_length2()) <= ref_distance2; -} -//////////////////////////////////////////////////////////////////////////////// -details::Index3 Config3d::index3_(const float32_t x, const float32_t y, const float32_t z) const -{ - return {x_index(x), y_index(y), z_index(z)}; // zero initialization -} -//////////////////////////////////////////////////////////////////////////////// -Index Config3d::index_(const details::Index3 & idx) const -{ - return bin_impl(idx.x, idx.y, idx.z); -} -//////////////////////////////////////////////////////////////////////////////// -template class SpatialHash; -template class SpatialHash; -} // namespace spatial_hash -} // namespace geometry -} // namespace common -} // namespace autoware diff --git a/common/autoware_auto_geometry/test/include/test_bounding_box.hpp b/common/autoware_auto_geometry/test/include/test_bounding_box.hpp deleted file mode 100644 index a179fbde5f151..0000000000000 --- a/common/autoware_auto_geometry/test/include/test_bounding_box.hpp +++ /dev/null @@ -1,550 +0,0 @@ -// Copyright 2017-2019 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. -// -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. - -#ifndef TEST_BOUNDING_BOX_HPP_ -#define TEST_BOUNDING_BOX_HPP_ - -#include "autoware_auto_geometry/bounding_box/lfit.hpp" -// cspell: ignore lfit -#include "autoware_auto_geometry/bounding_box/rotating_calipers.hpp" - -#include - -#include -#include -#include - -using autoware::common::geometry::point_adapter::x_; -using autoware::common::geometry::point_adapter::xr_; -using autoware::common::geometry::point_adapter::y_; -using autoware::common::geometry::point_adapter::yr_; -using autoware_auto_perception_msgs::msg::BoundingBox; - -template -class BoxTest : public ::testing::Test -{ -protected: - std::list points; - BoundingBox box; - - void minimum_area_bounding_box() - { - // apex_test_tools::memory_test::start(); - box = autoware::common::geometry::bounding_box::minimum_area_bounding_box(points); - // apex_test_tools::memory_test::stop(); - } - - void minimum_perimeter_bounding_box() - { - // apex_test_tools::memory_test::start(); - box = autoware::common::geometry::bounding_box::minimum_perimeter_bounding_box(points); - // apex_test_tools::memory_test::stop(); - } - - // cspell: ignore eigenbox - template - void eigenbox(const IT begin, const IT end) - { - // apex_test_tools::memory_test::start(); - box = autoware::common::geometry::bounding_box::eigenbox_2d(begin, end); - // apex_test_tools::memory_test::stop(); - } - template - void lfit_bounding_box_2d(const IT begin, const IT end) - { - // apex_test_tools::memory_test::start(); - box = autoware::common::geometry::bounding_box::lfit_bounding_box_2d(begin, end); - // apex_test_tools::memory_test::stop(); - } - - PointT make(const float x, const float y) - { - PointT ret; - xr_(ret) = x; - yr_(ret) = y; - return ret; - } - - void check(const float cx, const float cy, const float sx, const float sy, const float val) const - { - constexpr float32_t TOL = 1.0E-4F; - ASSERT_LT(fabsf(box.size.x - sx), TOL); - ASSERT_LT(fabsf(box.size.y - sy), TOL); - ASSERT_LT(fabsf(box.value - val), TOL) << box.value; - - ASSERT_LT(fabsf(box.centroid.x - cx), TOL); - ASSERT_LT(fabsf(box.centroid.y - cy), TOL); - } - - void test_corners(const std::vector & expect, const float TOL = 1.0E-6F) const - { - for (uint32_t idx = 0U; idx < 4U; ++idx) { - bool found = false; - for (auto & p : expect) { - if (fabsf(x_(p) - box.corners[idx].x) < TOL && fabsf(y_(p) - box.corners[idx].y) < TOL) { - found = true; - break; - } - } - ASSERT_TRUE(found) << idx << ": " << box.corners[idx].x << ", " << box.corners[idx].y; - } - } - - /// \brief th_deg - phi_deg, normalized to +/- 180 deg - float32_t angle_distance_deg(const float th_deg, const float phi_deg) const - { - return fmodf((th_deg - phi_deg) + 540.0F, 360.0F) - 180.0F; - } - - /// \brief converts a radian value to a degree value - float32_t rad2deg(const float rad_val) const { return rad_val * 57.2958F; } - - void test_orientation(const float ref_angle_deg, const float TOL = 1.0E-4F) const - { - bool found = false; - const float angle_deg = rad2deg(2.0F * asinf(box.orientation.z)); - found |= fabsf(angle_distance_deg(angle_deg, ref_angle_deg)) < TOL; - found |= fabsf(angle_distance_deg(angle_deg, ref_angle_deg + 90.0F)) < TOL; - found |= fabsf(angle_distance_deg(angle_deg, ref_angle_deg + 180.0F)) < TOL; - found |= fabsf(angle_distance_deg(angle_deg, ref_angle_deg + 270.0F)) < TOL; - ASSERT_TRUE(found) << angle_deg; - } -}; // BoxTest - -// Instantiate tests for given types, add more types here as they are used -using PointTypesBoundingBox = - ::testing::Types; -// cppcheck-suppress syntaxError -TYPED_TEST_SUITE(BoxTest, PointTypesBoundingBox, ); -/// NOTE: This is the older version due to 1.8.0 of GTest. v1.8.1 uses TYPED_TEST_SUITE - -// TODO(c.ho) consider typed and parameterized tests: -// https://stackoverflow.com/questions/3258230/passing-a-typename-and-string-to-parameterized-test-using-google-test - -/////////////////////////////////////////// -TYPED_TEST(BoxTest, PointSegmentDistance) -{ - using autoware::common::geometry::closest_segment_point_2d; - using autoware::common::geometry::point_line_segment_distance_2d; - // normal case - TypeParam p = this->make(-1.0F, 0.0F); - TypeParam q = this->make(-1.0F, 2.0F); - TypeParam r = this->make(1.0F, 1.0F); - TypeParam t = closest_segment_point_2d(p, q, r); - ASSERT_FLOAT_EQ(x_(t), -1.0F); - ASSERT_FLOAT_EQ(y_(t), 1.0F); - ASSERT_FLOAT_EQ(point_line_segment_distance_2d(p, q, r), 2.0F); - // boundary case - p = this->make(1.0F, 0.0F); - q = this->make(-2.0F, 0.0F); - r = this->make(-5.0F, 0.0F); - t = closest_segment_point_2d(p, q, r); - ASSERT_FLOAT_EQ(x_(t), -2.0F); - ASSERT_NEAR(y_(t), 0.0F, std::numeric_limits::epsilon()); - ASSERT_FLOAT_EQ(point_line_segment_distance_2d(p, q, r), 3.0F); - // singular case - p = this->make(1.0F, 5.0F); - q = this->make(1.0F, 5.0F); - r = this->make(1.0F, 1.0F); - t = closest_segment_point_2d(p, q, r); - ASSERT_FLOAT_EQ(x_(t), 1.0F); - ASSERT_FLOAT_EQ(y_(t), 5.0F); - ASSERT_FLOAT_EQ(point_line_segment_distance_2d(p, q, r), 4.0F); -} - -TYPED_TEST(BoxTest, ClosestPointOnLine) -{ - using autoware::common::geometry::closest_line_point_2d; - // normal case - TypeParam p = this->make(-1.0F, 0.0F); - TypeParam q = this->make(-1.0F, 2.0F); - TypeParam r = this->make(1.0F, 1.0F); - TypeParam t = closest_line_point_2d(p, q, r); - ASSERT_FLOAT_EQ(x_(t), -1.0F); - ASSERT_FLOAT_EQ(y_(t), 1.0F); - // out-of-boundary case - p = this->make(1.0F, 0.0F); - q = this->make(-2.0F, 0.0F); - r = this->make(-5.0F, 0.0F); - t = closest_line_point_2d(p, q, r); - ASSERT_FLOAT_EQ(x_(t), -5.0F); - ASSERT_NEAR(y_(t), 0.0F, std::numeric_limits::epsilon()); - // singular case - p = this->make(1.0F, 5.0F); - q = this->make(1.0F, 5.0F); - r = this->make(1.0F, 1.0F); - EXPECT_THROW(t = closest_line_point_2d(p, q, r), std::runtime_error); -} - -TYPED_TEST(BoxTest, Basic) -{ - const std::vector data{ - {this->make(0, 0), this->make(1, 0), this->make(1, 1), this->make(0, 1)}}; - this->points.insert(this->points.begin(), data.begin(), data.end()); - - this->minimum_area_bounding_box(); - - this->check(0.5F, 0.5F, 1.0F, 1.0F, 1.0F); - this->test_corners(data); - this->test_orientation(0.0F); - - this->minimum_perimeter_bounding_box(); - - this->check(0.5F, 0.5F, 1.0F, 1.0F, 2.0F); - this->test_corners(data); - this->test_orientation(0.0F); -} - -// -TYPED_TEST(BoxTest, OrientedTriangle) -{ - this->points.insert(this->points.begin(), {this->make(5, 5), this->make(7, 7), this->make(5, 7)}); - - this->minimum_area_bounding_box(); - - this->check(5.5F, 6.5F, sqrtf(2.0F), 2.0F * sqrtf(2.0F), 4.0F); - this->test_corners({this->make(5, 5), this->make(7, 7), this->make(4, 6), this->make(6, 8)}); - this->test_orientation(45.0F); - - this->minimum_perimeter_bounding_box(); - - this->check(6.0F, 6.0F, 2.0F, 2.0F, 4.0F); - this->test_corners({this->make(5, 5), this->make(7, 7), this->make(5, 7), this->make(7, 5)}); - this->test_orientation(0.0F); -} -// -TYPED_TEST(BoxTest, Hull) -{ - const uint32_t FUZZ_SIZE = 1024U; - const float dx = 9.0F; - const float dy = 15.0F; - const float rx = 10.0F; - const float ry = 5.0F; - const float dth = 0.0F; - - ASSERT_EQ(FUZZ_SIZE % 4U, 0U); - - // fuzz part 1 - for (uint32_t idx = 0U; idx < FUZZ_SIZE; ++idx) { - const float th = ((idx * autoware::common::types::TAU) / FUZZ_SIZE) + dth; - this->points.push_back(this->make(rx * cosf(th) + dx, ry * sinf(th) + dy)); - } - - this->minimum_area_bounding_box(); - - // allow 10cm = 2% of size for tolerance - const float TOL_M = 0.1F; - ASSERT_LT(fabsf(this->box.centroid.x - dx), TOL_M); - ASSERT_LT(fabsf(this->box.centroid.y - dy), TOL_M); - - this->test_corners( - {this->make(dx + rx, dy + ry), this->make(dx - rx, dy + ry), this->make(dx - rx, dy - ry), - this->make(dx + rx, dy - ry)}, - TOL_M); - - this->test_orientation(this->rad2deg(dth), 1.0F); - // allow 1 degree of tolerance - - ASSERT_LT(fabsf(this->box.size.y - 2.0F * rx), TOL_M); - ASSERT_LT(fabsf(this->box.size.x - 2.0F * ry), TOL_M); - ASSERT_FLOAT_EQ(this->box.value, this->box.size.x * this->box.size.y); -} - -// -TYPED_TEST(BoxTest, Collinear) -{ - this->points.insert( - this->points.begin(), {this->make(-2, -2), this->make(-3, -2), this->make(-4, -2), - this->make(-2, -4), this->make(-3, -4), this->make(-4, -4), - this->make(-2, -3), this->make(-2, -3), this->make(-2, -4)}); - - this->minimum_area_bounding_box(); - - this->check(-3.0F, -3.0F, 2.0F, 2.0F, 4.0F); - this->test_corners( - {this->make(-2, -2), this->make(-2, -4), this->make(-4, -4), this->make(-4, -2)}); - this->test_orientation(0.0F); -} - -// -TYPED_TEST(BoxTest, Line1) -{ - this->points.insert( - this->points.begin(), {this->make(-4, 3), this->make(-8, 6), this->make(-12, 9), - this->make(-16, 12), this->make(-20, 15), this->make(-24, 18), - this->make(-28, 21), this->make(-32, 24), this->make(-36, 27)}); - - this->minimum_area_bounding_box(); - - this->check(-20.0F, 15.0F, 1.0E-6F, 40.0F, 4.0E-5F); - this->test_orientation(this->rad2deg(atan2f(3, -4))); - this->test_corners( - {this->make(-4, 3), this->make(-30, 27), this->make(-4, 3), this->make(-36, 27)}); - - this->minimum_perimeter_bounding_box(); - - this->check(-20.0F, 15.0F, 1.0E-6F, 40.0F, 40.00001F); - this->test_orientation(this->rad2deg(atan2f(3, -4))); - this->test_corners( - {this->make(-4, 3), this->make(-30, 27), this->make(-4, 3), this->make(-36, 27)}); -} - -// -TYPED_TEST(BoxTest, Line2) -{ - this->points.insert( - this->points.begin(), - {this->make(4, 0), this->make(8, 0), this->make(12, 0), this->make(16, 0), this->make(20, 0), - this->make(24, 0), this->make(28, 0), this->make(32, 0), this->make(36, 0)}); - - this->minimum_area_bounding_box(); - - this->check(20.0F, 0.0F, 1.0E-6F, 32.0F, 3.2E-5F); - this->test_orientation(0.0F); - this->test_corners({this->make(4, 0), this->make(36, 0), this->make(4, 0), this->make(36, 0)}); -} - -// -TYPED_TEST(BoxTest, Line3) -{ - this->points.insert( - this->points.begin(), - {this->make(4, 3), this->make(8, 6), this->make(12, 9), this->make(16, 12), this->make(20, 15), - this->make(24, 18), this->make(28, 21), this->make(32, 24), this->make(36, 27)}); - - this->minimum_area_bounding_box(); - - this->check(20.0F, 15.0F, 1.0E-6F, 40.0F, 4.0E-5F); - this->test_orientation(this->rad2deg(atan2f(3, 4))); - this->test_corners({this->make(4, 3), this->make(36, 27), this->make(4, 3), this->make(36, 27)}); -} - -/* _ - /_/ <-- first guess is suboptimal - -*/ -TYPED_TEST(BoxTest, SuboptimalInit) -{ - this->points.insert( - this->points.begin(), - {this->make(8, 15), this->make(17, 0), this->make(0, 0), this->make(25, 15)}); - - this->minimum_area_bounding_box(); - - this->check(12.5F, 7.5F, 15.0F, 25.0F, 375.0F); - this->test_orientation(this->rad2deg(atan2f(15, 8))); - // these are approximate. - this->test_corners( - {this->make(0, 0), this->make(25, 15), this->make(11.7647F, 22.0588F), - this->make(13.2353F, -7.05882F)}, - 0.1F); -} - -// -TYPED_TEST(BoxTest, Centered) -{ - this->points.insert( - this->points.begin(), - {this->make(-1, 0), this->make(1, 0), this->make(0, -1), this->make(0, 1)}); - - this->minimum_area_bounding_box(); - - this->check(0.0F, 0.0F, sqrtf(2.0F), sqrtf(2.0F), 2.0F); - this->test_orientation(45.0F); - this->test_corners({this->make(-1, 0), this->make(1, 0), this->make(0, 1), this->make(0, -1)}); -} - -// convex_hull is imperfect in this case, check if this can save the day -TYPED_TEST(BoxTest, OverlappingPoints) -{ - this->points.insert( - this->points.begin(), {this->make(0, 0), this->make(1, 0), this->make(1, 1), this->make(0, 1), - this->make(0, 0), this->make(1, 0), this->make(1, 1), this->make(0, 1)}); - - this->minimum_area_bounding_box(); - - this->check(0.5F, 0.5F, 1.0F, 1.0F, 1.0F); - this->test_orientation(0.0F); - this->test_corners({this->make(0, 0), this->make(1, 0), this->make(0, 1), this->make(1, 1)}); -} - -// check that minimum perimeter box is different from minimum area box -TYPED_TEST(BoxTest, Perimeter) -{ - this->points.insert( - this->points.begin(), {this->make(0, 0), this->make(0, 1), this->make(0, 2), this->make(0, 3), - this->make(0, 4), this->make(1, -0.1), // small fudge to force diagonal - this->make(2, 0), this->make(3, 0)}); - - this->minimum_area_bounding_box(); - - this->check(0.54F, 1.28F, 5.0F, 12.0F / 5.0F, 12.0F); - this->test_orientation(-53.13F, 0.001F); - this->test_corners( - {this->make(3, 0), this->make(0, 4), this->make(-1.92, 2.56), this->make(1.08, -1.44)}); - - // eigenbox should produce AABB TODO(c.ho) - // compute minimum perimeter box - this->minimum_perimeter_bounding_box(); - this->check(1.5F, 1.95F, 4.1F, 3.0F, 7.1F); - // perimeter for first box would be 14.8 - this->test_orientation(0.0F, 0.001F); - this->test_corners( - {this->make(3, -0.1), this->make(0, 4), this->make(3, 4), this->make(0, -0.1)}); -} - -// bounding box is diagonal on an L -TYPED_TEST(BoxTest, Eigenbox1) -{ - std::vector v{this->make(0, 0), this->make(0, 1), - this->make(-1, 2), // small fudge to force diagonal - this->make(0, 3), this->make(0, 4), - this->make(1, 0), this->make(2, -1), // small fudge to force diagonal - this->make(3, 0), this->make(4, 0)}; - this->points.insert(this->points.begin(), v.begin(), v.end()); - - // rotating calipers should produce a diagonal box - this->minimum_area_bounding_box(); - const float r = 4.0F; - - this->check(1.0F, 1.0F, r / sqrtf(2.0F), sqrtf(2.0F) * r, r * r); - const std::vector diag_corners{ - this->make(4, 0), this->make(0, 4), this->make(-2, 2), this->make(2, -2)}; - this->test_corners(diag_corners); - this->test_orientation(45.0F, 0.001F); - - //// perimeter should also produce diagonal //// - this->minimum_perimeter_bounding_box(); - this->check( - 1.0F, 1.0F, r / sqrtf(2.0F), sqrtf(2.0F) * r, r * (sqrtf(2.0F) + (1.0F / sqrtf(2.0F)))); - this->test_corners(diag_corners); - this->test_orientation(45.0F, 0.001F); - //// eigenbox should also produce aabb //// - this->eigenbox(v.begin(), v.end()); - // TODO(c.ho) don't care about value.. - this->check(1.0F, 1.0F, r * sqrtf(2.0F), r / sqrtf(2.0F), 4.375F); - this->test_corners(diag_corners); - this->test_orientation(45.0F, 0.001F); - //// Lfit should produce aabb //// - this->lfit_bounding_box_2d(v.begin(), v.end()); - - this->test_corners( - {this->make(4, -1), this->make(-1, 4), this->make(4, 4), this->make(-1, -1)}, 0.25F); - this->test_orientation(0.0F, 3.0F); -} - -// same as above test, just rotated -TYPED_TEST(BoxTest, Eigenbox2) -{ - std::vector v{this->make(0, 0), this->make(1, 1), - this->make(1, 2), // small fudge to force diagonal - this->make(3, 3), this->make(4, 4), - this->make(1, -1), this->make(1, -2), // small fudge to force diagonal - this->make(3, -3), this->make(4, -4)}; - this->points.insert(this->points.begin(), v.begin(), v.end()); - - const std::vector diag_corners{ - this->make(4, 4), this->make(0, 4), this->make(0, -4), this->make(4, -4)}; - // rotating calipers should produce a aabb - this->minimum_area_bounding_box(); - this->check(2.0F, 0.0F, 8, 4, 32); - this->test_corners(diag_corners); - this->test_orientation(0.0F, 0.001F); - - //// perimeter should also produce aabb //// - this->minimum_perimeter_bounding_box(); - this->check(2.0F, 0.0F, 8, 4, 12); - this->test_corners(diag_corners); - - //// eigenbox should also produce obb //// - this->eigenbox(v.begin(), v.end()); - this->test_orientation(0.0F, 0.001F); - this->test_corners(diag_corners); - //// Lfit should produce obb //// - this->lfit_bounding_box_2d(v.begin(), v.end()); - this->test_corners( - {this->make(3.5, 4.5), this->make(-1, 0), this->make(3.5, -4.5), this->make(8, 0)}, 0.2F); - this->test_orientation(45.0F, 2.0F); -} -// line case for eigenbox -TYPED_TEST(BoxTest, Eigenbox3) -{ - // horizontal line with some noise - std::vector v{this->make(0, 0.00), this->make(1, -0.01), this->make(3, 0.02), - this->make(3, 0.03), this->make(4, -0.04), this->make(-1, 0.01), - this->make(-2, -0.02), this->make(-3, -0.03), this->make(-4, 0.04)}; - this->lfit_bounding_box_2d(v.begin(), v.end()); - this->test_corners( - {this->make(-4, -0.04), this->make(-4, 0.04), this->make(4, -0.04), this->make(4, 0.04)}, 0.2F); - this->test_orientation(0.0F, 1.0F); -} - -// bad case: causes intersection2d to fail -// See https://gitlab.apex.ai/ApexAI/grand_central/issues/2862#note_156875 for more failure cases -TYPED_TEST(BoxTest, IntersectFail) -{ - std::vector vals{ - this->make(-13.9, 0.100006), this->make(-14.1, 0.100006), this->make(-13.9, 0.300003), - this->make(-14.1, 0.300003), this->make(-13.9, 0.5), this->make(-14.1, 0.5), - this->make(-13.9, 0.699997), this->make(-14.1, 0.699997), this->make(-14.3, 0.699997)}; - EXPECT_NO_THROW(this->lfit_bounding_box_2d(vals.begin(), vals.end())); - vals = {this->make(-2.1, 10.1), this->make(-1.89999, 10.1), this->make(-1.89999, 10.3), - this->make(-1.7, 10.3), this->make(-1.5, 10.3), this->make(-1.3, 10.3), - this->make(-0.5, 10.3), this->make(-0.300003, 10.3), this->make(-0.0999908, 10.3), - this->make(0.699997, 10.3), this->make(0.900009, 10.3), this->make(1.3, 10.3), - this->make(1.7, 10.3)}; - EXPECT_NO_THROW(this->lfit_bounding_box_2d(vals.begin(), vals.end())); - vals = {this->make(2.7, -5.5), this->make(2.7, -5.3), this->make(2.7, -5.1), - this->make(2.7, -4.9), this->make(2.7, -4.7), this->make(2.7, -4.5), - this->make(2.7, -4.3), this->make(2.7, -4.1), this->make(2.7, -3.9)}; - EXPECT_NO_THROW(this->lfit_bounding_box_2d(vals.begin(), vals.end())); -} -/// Handle slight floating point underflow case -// Note: raw discriminant checks are disabled because they don't work. I suspect this is due to -// tiny differences in floating point math when using our compile flags -TYPED_TEST(BoxTest, EigUnderflow) -{ - using autoware::common::geometry::bounding_box::details::Covariance2d; - // auto discriminant = [](const Covariance2d cov) -> float32_t { - // // duplicated raw math - // const float32_t tr_2 = (cov.xx + cov.yy) * 0.5F; - // const float32_t det = (cov.xx * cov.yy) - (cov.xy * cov.xy); - // return (tr_2 * tr_2) - det; - // }; - TypeParam u, v; - const Covariance2d c1{0.0300002, 0.0300002, 5.46677e-08, 0U}; - // EXPECT_LT(discriminant(c1), 0.0F); - EXPECT_NO_THROW(autoware::common::geometry::bounding_box::details::eig_2d(c1, u, v)); - const Covariance2d c2{0.034286, 0.0342847, 2.12874e-09, 0U}; - // EXPECT_LT(discriminant(c2), 0.0F); - EXPECT_NO_THROW(autoware::common::geometry::bounding_box::details::eig_2d(c2, u, v)); - const Covariance2d c3{0.0300002, 0.0300002, -2.84987e-08, 0U}; - // EXPECT_LT(discriminant(c3), 0.0F); - EXPECT_NO_THROW(autoware::common::geometry::bounding_box::details::eig_2d(c3, u, v)); - const Covariance2d c4{0.0300004, 0.0300002, 3.84156e-08, 0U}; - // EXPECT_LT(discriminant(c4), 0.0F); - EXPECT_NO_THROW(autoware::common::geometry::bounding_box::details::eig_2d(c4, u, v)); - const Covariance2d c5{0.0300014, 0.0300014, -7.45058e-09, 0U}; - // EXPECT_LT(discriminant(c5), 0.0F); - EXPECT_NO_THROW(autoware::common::geometry::bounding_box::details::eig_2d(c5, u, v)); - const Covariance2d c6{0.0400004, 0.0400002, 3.28503e-08, 0U}; - // EXPECT_LT(discriminant(c6), 0.0F); - EXPECT_NO_THROW(autoware::common::geometry::bounding_box::details::eig_2d(c6, u, v)); -} - -//////////////////////////////////////////////// - -#endif // TEST_BOUNDING_BOX_HPP_ diff --git a/common/autoware_auto_geometry/test/include/test_spatial_hash.hpp b/common/autoware_auto_geometry/test/include/test_spatial_hash.hpp deleted file mode 100644 index fc2d97c257b95..0000000000000 --- a/common/autoware_auto_geometry/test/include/test_spatial_hash.hpp +++ /dev/null @@ -1,260 +0,0 @@ -// Copyright 2019 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. -// -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. - -#ifndef TEST_SPATIAL_HASH_HPP_ -#define TEST_SPATIAL_HASH_HPP_ - -#include "autoware_auto_geometry/spatial_hash.hpp" - -#include - -#include -#include - -using autoware::common::geometry::spatial_hash::Config2d; -using autoware::common::geometry::spatial_hash::Config3d; -using autoware::common::geometry::spatial_hash::SpatialHash; -using autoware::common::geometry::spatial_hash::SpatialHash2d; -using autoware::common::geometry::spatial_hash::SpatialHash3d; -using autoware::common::types::bool8_t; -using autoware::common::types::float32_t; -using autoware::common::types::float64_t; - -template -class TypedSpatialHashTest : public ::testing::Test -{ -public: - TypedSpatialHashTest() : ref(), EPS(0.001F) - { - ref.x = 0.0F; - ref.y = 0.0F; - ref.z = 0.0F; - } - -protected: - template - void add_points( - SpatialHash & hash, const uint32_t points_per_ring, const uint32_t num_rings, - const float32_t dr, const float32_t dx = 0.0F, const float32_t dy = 0.0F) - { - const float32_t dth = 2.0F * 3.14159F / points_per_ring; - - // insert - float32_t r = dr; - for (uint32_t rdx = 0U; rdx < num_rings; ++rdx) { - float32_t th = 0.0F; - for (uint32_t pdx = 0U; pdx < points_per_ring; ++pdx) { - PointT pt; - pt.x = r * cosf(th) + dx; - pt.y = r * sinf(th) + dy; - pt.z = 0.0F; - hash.insert(pt); - th += dth; - } - r += dr; - } - } - PointT ref; - const float32_t EPS; -}; // SpatialHash -// test struct - -// Instantiate tests for given types, add more types here as they are used -using PointTypesSpatialHash = ::testing::Types; -// cppcheck-suppress syntaxError -TYPED_TEST_SUITE(TypedSpatialHashTest, PointTypesSpatialHash, ); -/// NOTE: This is the older version due to 1.8.0 of GTest. v1.8.1 uses TYPED_TEST_SUITE - -/////////////////////////////////////////////////////////////// -// TODO(christopher.ho) helper functions to simplify this stuff -/// all points in one bin -TYPED_TEST(TypedSpatialHashTest, OneBin) -{ - using PointT = TypeParam; - const float32_t dr = 1.0F; - Config2d cfg{-10.0F, 10.0F, -10.0F, 10.0F, 3.0F, 1024U}; - SpatialHash2d hash{cfg}; - - // build concentric rings around origin - const uint32_t PTS_PER_RING = 10U; - const uint32_t NUM_RINGS = 1U; - this->add_points(hash, PTS_PER_RING, NUM_RINGS, dr); - - // loop through all points - float r = dr - this->EPS; - for (uint32_t rdx = 0U; rdx < NUM_RINGS + 1U; ++rdx) { - const uint32_t n_pts = rdx * PTS_PER_RING; - const auto & neighbors = hash.near(this->ref, r); - uint32_t points_seen = 0U; - for (const auto & itd : neighbors) { - const PointT & pt = itd; - const float dist = sqrtf((pt.x * pt.x) + (pt.y * pt.y)); - ASSERT_LT(dist, r); - ASSERT_FLOAT_EQ(dist, itd.get_distance()); - ++points_seen; - } - ASSERT_EQ(points_seen, n_pts); - r += dr; - // Make sure statistics are consistent - EXPECT_EQ(hash.bins_hit(), 9U * (1U + rdx)); - EXPECT_EQ(hash.neighbors_found(), rdx * PTS_PER_RING); - } - // check iterators etc. - uint32_t count = 0U; - for (auto iter = hash.cbegin(); iter != hash.cend(); ++iter) { - // TODO(c.ho) check uniqueness of stuff - ++count; - } - EXPECT_EQ(PTS_PER_RING, count); - hash.clear(); - EXPECT_EQ(hash.size(), 0U); - EXPECT_TRUE(hash.empty()); - count = 0U; - for (auto it : hash) { - // TODO(c.ho) check uniqueness of stuff - (void)it; - ++count; - } - EXPECT_EQ(count, 0U); -} -/// test out of bounds points -TYPED_TEST(TypedSpatialHashTest, Oob) -{ - using PointT = TypeParam; - const float32_t dr = 20.0F; - Config2d cfg{-2.0F, 2.0F, -2.0F, 2.0F, dr + this->EPS, 1024U}; - SpatialHash2d hash{cfg}; - - // build concentric rings around origin - const uint32_t PTS_PER_RING = 12U; - this->add_points(hash, PTS_PER_RING, 1U, dr); - - // loop through all points - float32_t r = dr + this->EPS; - const uint32_t n_pts = PTS_PER_RING; - const auto & neighbors = hash.near(this->ref, r); - uint32_t points_seen = 0U; - for (const auto itd : neighbors) { - const PointT & pt = itd; - const float32_t dist = sqrtf((pt.x * pt.x) + (pt.y * pt.y)); - ASSERT_LT(dist, r); - ASSERT_GT(dist, 10.0F * sqrtf(2.0F)); - ASSERT_FLOAT_EQ(dist, itd.get_distance()); - ++points_seen; - } - - ASSERT_EQ(points_seen, n_pts); -} -// 3d test case -TYPED_TEST(TypedSpatialHashTest, 3d) -{ - using PointT = TypeParam; - Config3d cfg{-30.0F, 30.0F, -30.0F, 30.0F, -30.0F, 30.0F, 30.0F, 1024U}; - SpatialHash3d hash{cfg}; - EXPECT_TRUE(hash.empty()); - - // build concentric rings around origin - const uint32_t points_per_ring = 32U; - const uint32_t num_rings = 5U; - const float32_t dth = 2.0F * 3.14159F / points_per_ring; - std::vector pts{}; - - // insert - const float32_t r = 10.0F; - float32_t phi = 0.0f; - for (uint32_t rdx = 0U; rdx < num_rings; ++rdx) { - float32_t th = 0.0F; - for (uint32_t pdx = 0U; pdx < points_per_ring; ++pdx) { - PointT pt; - pt.x = r * cosf(th) * cosf(phi); - pt.y = r * sinf(th) * cosf(phi); - pt.z = r * sinf(phi); - pts.push_back(pt); - th += dth; - } - hash.insert(pts.begin(), pts.end()); - pts.clear(); - phi += 1.0f; - } - EXPECT_FALSE(hash.empty()); - EXPECT_EQ(hash.size(), num_rings * points_per_ring); - - // loop through all points - const uint32_t n_pts = num_rings * points_per_ring; - const auto & neighbors = hash.near(this->ref, r + this->EPS); - uint32_t points_seen = 0U; - for (const auto & itd : neighbors) { - const PointT & pt = itd; - const float32_t dist = sqrtf((pt.x * pt.x) + (pt.y * pt.y) + (pt.z * pt.z)); - ASSERT_LT(dist, r + this->EPS); - ASSERT_FLOAT_EQ(dist, itd.get_distance()); - ++points_seen; - } - - ASSERT_EQ(points_seen, n_pts); - - // check iterators etc. - uint32_t count = 0U; - for (auto iter = hash.cbegin(); iter != hash.cend(); ++iter) { - // TODO(c.ho) check uniqueness of stuff - ++count; - } - EXPECT_EQ(n_pts, count); - hash.clear(); - EXPECT_EQ(hash.size(), 0U); - EXPECT_TRUE(hash.empty()); - count = 0U; - for (auto it : hash) { - // TODO(c.ho) check uniqueness of stuff - (void)it; - ++count; - } - EXPECT_EQ(count, 0U); -} - -/// edge cases -TEST(SpatialHashConfig, BadCases) -{ - // negative side length - EXPECT_THROW(Config2d({-30.0F, 30.0F, -30.0F, 30.0F, -1.0F, 1024U}), std::domain_error); - // min_x >= max_x - EXPECT_THROW(Config2d({31.0F, 30.0F, -30.0F, 30.0F, 1.0F, 1024U}), std::domain_error); - // min_y >= max_y - EXPECT_THROW(Config2d({-30.0F, 30.0F, 30.1F, 30.0F, 1.0F, 1024U}), std::domain_error); - // min_z >= max_z - EXPECT_THROW( - Config3d({-30.0F, 30.0F, -30.0F, 30.0F, 31.0F, 30.0F, 1.0F, 1024U}), std::domain_error); - // floating point limit - constexpr float32_t max_float = std::numeric_limits::max(); - EXPECT_THROW(Config2d({-max_float, max_float, -30.0F, 30.0F, 1.0F, 1024U}), std::domain_error); - EXPECT_THROW( - Config3d({-30.0F, 30.0F, -max_float, max_float, -30.0F, 30.0F, 1.0F, 1024U}), - std::domain_error); - EXPECT_THROW( - Config3d({-30.0F, 30.0F, -30.0F, 30.0F, -max_float, max_float, 1.0F, 1024U}), - std::domain_error); - // y would overflow - // constexpr float32_t big_float = - // static_cast(std::numeric_limits::max() / 4UL); - // EXPECT_THROW(Config({-big_float, big_float, -big_float, big_float, 0.001F, 1024U}), - // std::domain_error); - // z would overflow - // EXPECT_THROW( - // Config3d({-30.0F, 30.0F, -99999.0F, 99999.0F, -99999.0F, 99999.0F, 0.001F, 1024U}), - // std::domain_error); - // TODO(c.ho) re-enable test when we can actually check unsigned integer multiplication overflow -} -#endif // TEST_SPATIAL_HASH_HPP_ diff --git a/common/autoware_auto_geometry/test/src/lookup_table.cpp b/common/autoware_auto_geometry/test/src/lookup_table.cpp deleted file mode 100644 index 81865656c55b5..0000000000000 --- a/common/autoware_auto_geometry/test/src/lookup_table.cpp +++ /dev/null @@ -1,166 +0,0 @@ -// Copyright 2017-2020 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. -// -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. - -#include "autoware_auto_geometry/lookup_table.hpp" - -#include - -#include - -#include -#include - -using autoware::common::helper_functions::interpolate; -using autoware::common::helper_functions::lookup_1d; -using autoware::common::helper_functions::LookupTable1D; -using autoware::common::types::float32_t; -using autoware::common::types::float64_t; - -template -class BadCase : public ::testing::Test -{ -}; - -using BadTypes = ::testing::Types; -// cppcheck-suppress syntaxError -TYPED_TEST_SUITE(BadCase, BadTypes, ); - -// Empty domain/range -TYPED_TEST(BadCase, Empty) -{ - using T = TypeParam; - EXPECT_THROW(lookup_1d({}, {}, T{}), std::domain_error); -} - -// Unequal domain/range -TYPED_TEST(BadCase, UnequalDomain) -{ - using T = TypeParam; - EXPECT_THROW(lookup_1d({T{1}, T{2}}, {T{1}}, T{}), std::domain_error); -} - -// Not sorted domain -TYPED_TEST(BadCase, DomainNotSorted) -{ - using T = TypeParam; - EXPECT_THROW(lookup_1d({T{2}, T{1}}, {T{1}, T{2}}, T{}), std::domain_error); -} - -//////////////////////////////////////////////////////////////////////////////// - -template -class SanityCheck : public ::testing::Test -{ -public: - using T = Type; - - void SetUp() override - { - domain_ = std::vector{T{1}, T{3}, T{5}}; - range_ = std::vector{T{2}, T{4}, T{0}}; - ASSERT_NO_THROW(table_ = std::make_unique>(domain_, range_)); - } - - bool not_in_domain(const T bad_value) const noexcept - { - return std::find(domain_.begin(), domain_.end(), bad_value) == domain_.end(); - } - - void check(const T expected, const T actual) const noexcept - { - if (std::is_floating_point::value) { - EXPECT_FLOAT_EQ(actual, expected); - } else { - EXPECT_EQ(actual, expected); - } - } - -protected: - std::vector domain_{}; - std::vector range_{}; - std::unique_ptr> table_{}; -}; - -using NormalTypes = ::testing::Types; -TYPED_TEST_SUITE(SanityCheck, NormalTypes, ); - -TYPED_TEST(SanityCheck, Exact) -{ - const auto x = this->domain_[1U]; - const auto result = this->table_->lookup(x); - ASSERT_FALSE(this->not_in_domain(x)); - this->check(result, this->range_[1U]); -} - -TYPED_TEST(SanityCheck, Interpolation) -{ - const auto x = TypeParam{2}; - // Assert x is not identically in domain_ - ASSERT_TRUE(this->not_in_domain(x)); - const auto result = this->table_->lookup(x); - this->check(result, TypeParam{3}); -} - -TYPED_TEST(SanityCheck, AboveRange) -{ - const auto x = TypeParam{999999}; - ASSERT_GT(x, this->domain_.back()); // domain is known to be sorted - const auto result = this->table_->lookup(x); - this->check(result, this->range_.back()); -} - -TYPED_TEST(SanityCheck, BelowRange) -{ - const auto x = TypeParam{0}; - ASSERT_LT(x, this->domain_.front()); // domain is known to be sorted - const auto result = this->table_->lookup(x); - this->check(result, this->range_.front()); -} - -TEST(LookupTableHelpers, Interpolate) -{ - { - const auto scaling = 0.0f; - EXPECT_EQ(interpolate(0.0f, 1.0f, scaling), 0.0f); - EXPECT_EQ(interpolate(2.0f, 3.5f, scaling), 2.0f); - } - - { - const auto scaling = 1.0f; - EXPECT_EQ(interpolate(0.0f, 1.0f, scaling), 1.0f); - EXPECT_EQ(interpolate(2.0f, 3.5f, scaling), 3.5f); - } - - { - const auto scaling = -1.0f; - EXPECT_EQ(interpolate(0.0f, 1.0f, scaling), 0.0f); - EXPECT_EQ(interpolate(2.0f, 3.5f, scaling), 2.0f); - } - - { - const auto scaling = 2.0f; - EXPECT_EQ(interpolate(0.0f, 1.0f, scaling), 1.0f); - EXPECT_EQ(interpolate(2.0f, 3.5f, scaling), 3.5f); - } - - { - const auto scaling = 0.75f; - EXPECT_EQ(interpolate(0.0f, 1.0f, scaling), 0.75f); - EXPECT_EQ(interpolate(2.0f, 3.5f, scaling), 3.125f); - } -} - -// TODO(c.ho) check with more interesting functions diff --git a/common/autoware_auto_geometry/test/src/test_area.cpp b/common/autoware_auto_geometry/test/src/test_area.cpp deleted file mode 100644 index bc9c28682ed44..0000000000000 --- a/common/autoware_auto_geometry/test/src/test_area.cpp +++ /dev/null @@ -1,132 +0,0 @@ -// Copyright 2021 Apex.AI, 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. -// -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. - -#include "autoware_auto_geometry/common_2d.hpp" - -#include - -#include - -#include -#include -#include - -template -class AreaTest : public ::testing::Test -{ -protected: - DataStructure data_{}; - using Point = typename DataStructure::value_type; - using Real = decltype(autoware::common::geometry::point_adapter::x_(std::declval())); - - auto area() { return autoware::common::geometry::area_checked_2d(data_.begin(), data_.end()); } - - void add_point(Real x, Real y) - { - namespace pa = autoware::common::geometry::point_adapter; - Point p{}; - pa::xr_(p) = x; - pa::yr_(p) = y; - (void)data_.insert(data_.end(), p); - } -}; - -// Data structures to test... -template -using TestTypes_ = ::testing::Types..., std::list...>; -// ... and point types to test -using TestTypes = TestTypes_; -// cppcheck-suppress syntaxError -TYPED_TEST_SUITE(AreaTest, TestTypes, ); - -// The empty set has zero area -TYPED_TEST(AreaTest, DegenerateZero) -{ - EXPECT_FLOAT_EQ(0.0, this->area()); -} - -// An individual point has zero area -TYPED_TEST(AreaTest, DegenerateOne) -{ - this->add_point(0.0, 0.0); - EXPECT_FLOAT_EQ(0.0, this->area()); -} - -// An line segment has zero area -TYPED_TEST(AreaTest, DegenerateTwo) -{ - this->add_point(1.0, -1.0); - this->add_point(-3.0, 2.0); - EXPECT_FLOAT_EQ(0.0, this->area()); -} - -// Simple triangle -TYPED_TEST(AreaTest, Triangle) -{ - this->add_point(1.0, 0.0); - this->add_point(3.0, 0.0); // 2.0 wide - this->add_point(2.0, 2.0); // 2.0 tall - EXPECT_FLOAT_EQ(2.0, this->area()); // A = (1/2) * b * h -} - -// Rectangle is easy to do computational -TYPED_TEST(AreaTest, Rectangle) -{ - this->add_point(-5.0, -5.0); - this->add_point(-2.0, -5.0); // L = 3 - this->add_point(-2.0, -1.0); // H = 4 - this->add_point(-5.0, -1.0); - EXPECT_FLOAT_EQ(12.0, this->area()); // A = b * h -} - -// Parallelogram is slightly less trivial than a rectangle -TYPED_TEST(AreaTest, Parallelogram) -{ - this->add_point(-5.0, 1.0); - this->add_point(-2.0, 1.0); // L = 3 - this->add_point(-1.0, 3.0); // H = 2 - this->add_point(-4.0, 3.0); - EXPECT_FLOAT_EQ(6.0, this->area()); // A = b * h -} - -// Octagon is analytical and reasonably easy to build -TYPED_TEST(AreaTest, Octagon) -{ - const auto sq2 = std::sqrt(2.0); - const auto a = 1.0; - const auto a2 = a / 2.0; - const auto b = (a + sq2) / 2.0; - this->add_point(-a2, -b); - this->add_point(a2, -b); - this->add_point(b, -a2); - this->add_point(b, a2); - this->add_point(a2, b); - this->add_point(-a2, b); - this->add_point(-b, a2); - this->add_point(-b, -a2); - const auto expect = (2.0 * (1.0 + sq2)) * (a * a); - EXPECT_FLOAT_EQ(expect, this->area()); // A = b * h -} - -// Bad case -TYPED_TEST(AreaTest, NotCcw) -{ - this->add_point(0.0, 0.0); - this->add_point(1.0, 1.0); - this->add_point(1.0, 0.0); - this->add_point(2.0, 1.0); - EXPECT_THROW(this->area(), std::domain_error); -} diff --git a/common/autoware_auto_geometry/test/src/test_common_2d.cpp b/common/autoware_auto_geometry/test/src/test_common_2d.cpp deleted file mode 100644 index baf6967edd47e..0000000000000 --- a/common/autoware_auto_geometry/test/src/test_common_2d.cpp +++ /dev/null @@ -1,197 +0,0 @@ -// Copyright 2021 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. -// -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. - -#include "autoware_auto_geometry/common_2d.hpp" - -#include -#include - -#include - -#include -#include - -using autoware::common::geometry::point_adapter::xr_; -using autoware::common::geometry::point_adapter::yr_; - -// Helper function for adding new points -template -T make_points(const float x, const float y) -{ - T ret; - xr_(ret) = x; - yr_(ret) = y; - return ret; -} - -// PointTypes to be tested -using PointTypes = - ::testing::Types; - -// Wrapper function for stubbing output of -// autoware::common::geometry::check_point_position_to_line_2d -template -int point_position_checker(const T & p1, const T & p2, const T & q) -{ - auto result = autoware::common::geometry::check_point_position_to_line_2d(p1, p2, q); - if (result > 0.0F) { - return 1; - } else if (result < 0.0F) { - return -1; - } - return result; -} - -// Templated struct defining the function parameters for -// autoware::common::geometry::check_point_position_to_line_2d and input_output vector for -// assertion of return values from the function -template -struct PointPositionToLine : public ::testing::Test -{ - struct Parameters - { - T p1; - T p2; - T q; - }; - static std::vector> input_output; -}; - -TYPED_TEST_SUITE_P(PointPositionToLine); - -template -std::vector::Parameters, int>> - PointPositionToLine::input_output{ - {{make_points(0.0F, 0.0F), make_points(-1.0F, 1.0F), make_points(1.0F, 5.0F)}, -1}, - {{make_points(0.0F, 0.0F), make_points(-1.0F, 1.0F), make_points(-1.0F, 0.5F)}, 1}, - // Check point on the line - {{make_points(0.0F, 0.0F), make_points(-1.0F, 1.0F), make_points(-2.0F, 2.0F)}, 0}, - }; - -TYPED_TEST_P(PointPositionToLine, PointPositionToLineTest) -{ - for (size_t i = 0; i < PointPositionToLine::input_output.size(); ++i) { - const auto & input = PointPositionToLine::input_output[i].first; - EXPECT_EQ( - point_position_checker(input.p1, input.p2, input.q), - PointPositionToLine::input_output[i].second) - << "Index " << i; - } -} - -REGISTER_TYPED_TEST_SUITE_P(PointPositionToLine, PointPositionToLineTest); -// cppcheck-suppress syntaxError -INSTANTIATE_TYPED_TEST_SUITE_P(Test, PointPositionToLine, PointTypes, ); - -///////////////////////////////////////////////////////////////////////////////////// - -// Templated struct defining the function parameters for -// autoware::common::geometry::is_point_inside_polygon_2d and input_output vector for -// assertion of return values from the function -template -struct InsidePolygon : public ::testing::Test -{ - struct Parameters - { - std::vector polygon; - T q; - }; - static std::vector> input_output; -}; - -TYPED_TEST_SUITE_P(InsidePolygon); - -template -std::vector::Parameters, bool>> InsidePolygon::input_output{ - // point inside the rectangle - {{{make_points(0.0F, 0.0F), make_points(1.0F, 1.0F), make_points(0.5F, 1.5F), - make_points(-0.5F, 0.5F)}, - make_points(0.F, 0.5F)}, - true}, - // point below the rectangle - {{{make_points(0.0F, 0.0F), make_points(1.0F, 1.0F), make_points(0.5F, 1.5F), - make_points(-0.5F, 0.5F)}, - make_points(0.5F, 0.F)}, - false}, - // point above the rectangle - {{{make_points(0.0F, 0.0F), make_points(1.0F, 1.0F), make_points(0.5F, 1.5F), - make_points(-0.5F, 0.5F)}, - make_points(0.5F, 1.75F)}, - false}, - // point on the rectangle - {{{make_points(0.0F, 0.0F), make_points(1.0F, 1.0F), make_points(0.5F, 1.5F), - make_points(-0.5F, 0.5F)}, - make_points(0.5F, 0.5F)}, - true}, -}; - -TYPED_TEST_P(InsidePolygon, InsidePolygonTest) -{ - for (size_t i = 0; i < InsidePolygon::input_output.size(); ++i) { - const auto & input = InsidePolygon::input_output[i].first; - EXPECT_EQ( - autoware::common::geometry::is_point_inside_polygon_2d( - input.polygon.begin(), input.polygon.end(), input.q), - InsidePolygon::input_output[i].second) - << "Index " << i; - } -} - -REGISTER_TYPED_TEST_SUITE_P(InsidePolygon, InsidePolygonTest); -// cppcheck-suppress syntaxError -INSTANTIATE_TYPED_TEST_SUITE_P(Test, InsidePolygon, PointTypes, ); - -TEST(ordered_check, basic) -{ - // CW - std::vector points_list = { - make_points(8.0, 4.0), - make_points(9.0, 1.0), - make_points(3.0, 2.0), - make_points(2.0, 5.0)}; - EXPECT_TRUE(autoware::common::geometry::all_ordered(points_list.begin(), points_list.end())); - - // CCW - points_list = { - make_points(2.0, 5.0), - make_points(3.0, 2.0), - make_points(9.0, 1.0), - make_points(8.0, 4.0)}; - EXPECT_TRUE(autoware::common::geometry::all_ordered(points_list.begin(), points_list.end())); - - // Unordered - points_list = { - make_points(2.0, 5.0), - make_points(3.0, 2.0), - make_points(8.0, 4.0), - make_points(9.0, 1.0)}; - EXPECT_FALSE(autoware::common::geometry::all_ordered(points_list.begin(), points_list.end())); - - // Unordered - points_list = { - make_points(0.0, 0.0), - make_points(1.0, 1.0), - make_points(1.0, 0.0), - make_points(2.0, 1.0)}; - EXPECT_FALSE(autoware::common::geometry::all_ordered(points_list.begin(), points_list.end())); - - // Collinearity - points_list = { - make_points(2.0, 2.0), - make_points(4.0, 4.0), - make_points(6.0, 6.0)}; - EXPECT_TRUE(autoware::common::geometry::all_ordered(points_list.begin(), points_list.end())); -} diff --git a/common/autoware_auto_geometry/test/src/test_convex_hull.cpp b/common/autoware_auto_geometry/test/src/test_convex_hull.cpp deleted file mode 100644 index 8b9bbce36c428..0000000000000 --- a/common/autoware_auto_geometry/test/src/test_convex_hull.cpp +++ /dev/null @@ -1,372 +0,0 @@ -// Copyright 2017-2019 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. -// -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. - -#include "autoware_auto_geometry/convex_hull.hpp" - -#include - -#include - -#include -#include - -using autoware::common::types::bool8_t; -using autoware::common::types::float32_t; -using autoware::common::types::float64_t; - -template -class TypedConvexHullTest : public ::testing::Test -{ -protected: - std::list list; - - typename std::list::const_iterator convex_hull() - { - const auto ret = autoware::common::geometry::convex_hull(list); - return ret; - } - - void check_hull( - const typename std::list::const_iterator last, const std::vector & expect, - const bool8_t strict = true) - { - uint32_t items = 0U; - for (auto & pt : expect) { - bool8_t found = false; - auto it = list.begin(); - while (it != last) { - constexpr float32_t TOL = 1.0E-6F; - if ( - fabsf(pt.x - it->x) <= TOL && fabsf(pt.y - it->y) <= TOL && - (fabsf(pt.z - it->z) <= TOL || !strict)) // TODO(@estive): z if only strict - { - found = true; - break; - } - ++it; - } - ASSERT_TRUE(found) << items; - ++items; - } - if (strict) { - ASSERT_EQ(items, expect.size()); - } - } - - PointT make(const float32_t x, const float32_t y, const float32_t z) - { - PointT ret; - ret.x = x; - ret.y = y; - ret.z = z; - return ret; - } -}; // class convex_hull_test - -// Instantiate tests for given types, add more types here as they are used -using PointTypes = ::testing::Types; -// cppcheck-suppress syntaxError -TYPED_TEST_SUITE(TypedConvexHullTest, PointTypes, ); -/// NOTE: This is the older version due to 1.8.0 of GTest. v1.8.1 uses TYPED_TEST_SUITE - -////////////////////////////////////////// - -/* - 3 - 2 -1 -*/ -TYPED_TEST(TypedConvexHullTest, Triangle) -{ - std::vector expect({this->make(1, 0, 0), this->make(3, 1, 0), this->make(2, 2, 0)}); - this->list.insert(this->list.begin(), expect.begin(), expect.end()); - - const auto last = this->convex_hull(); - - this->check_hull(last, expect); - ASSERT_EQ(this->list.size(), 3U); - // check order - auto it = this->list.begin(); - ASSERT_FLOAT_EQ(it->x, 1); - ++it; // node 1 - ASSERT_FLOAT_EQ(it->x, 3); - ++it; // node 2 - ASSERT_FLOAT_EQ(it->x, 2); - ++it; // node 3 - ASSERT_EQ(it, last); -} -/* - 2 1 - -4 - 3 -*/ -// test that things get reordered to ccw -TYPED_TEST(TypedConvexHullTest, Quadrilateral) -{ - std::vector expect( - {this->make(-1, -1, 1), this->make(-5, -1, 2), this->make(-2, -6, 3), this->make(-6, -5, 4)}); - this->list.insert(this->list.begin(), expect.begin(), expect.end()); - const auto last = this->convex_hull(); - - this->check_hull(last, expect); - ASSERT_EQ(this->list.size(), 4U); - - // check for order - auto it = this->list.begin(); - ASSERT_FLOAT_EQ(it->x, -6); - ++it; // node 4 - ASSERT_FLOAT_EQ(it->x, -2); - ++it; // node 3 - ASSERT_FLOAT_EQ(it->x, -1); - ++it; // node 1 - ASSERT_FLOAT_EQ(it->x, -5); - ++it; // node 2 - ASSERT_EQ(it, last); -} - -// test that things get reordered to ccw -TYPED_TEST(TypedConvexHullTest, QuadHull) -{ - std::vector data( - {this->make(1, 1, 1), this->make(5, 1, 2), this->make(2, 6, 3), this->make(3, 3, 4), - this->make(6, 5, 5)}); - std::vector expect{{data[0], data[1], data[2], data[4]}}; - this->list.insert(this->list.begin(), data.begin(), data.end()); - - const auto last = this->convex_hull(); - - this->check_hull(last, expect); - ASSERT_EQ(std::distance(this->list.cbegin(), last), 4U); - - // check for order - auto it = this->list.begin(); - ASSERT_FLOAT_EQ(it->x, 1); - ++it; // node 1 - ASSERT_FLOAT_EQ(it->x, 5); - ++it; // node 2 - ASSERT_FLOAT_EQ(it->x, 6); - ++it; // node 4 - ASSERT_FLOAT_EQ(it->x, 2); - ++it; // node 3 - ASSERT_EQ(it, last); -} - -// a ring plus a bunch of random stuff in the middle -TYPED_TEST(TypedConvexHullTest, Hull) -{ - const uint32_t HULL_SIZE = 13U; - const uint32_t FUZZ_SIZE = 50U; - const float32_t dth = 1.133729384F; // some weird irrational(ish) number - const float32_t r_hull = 20.0F; - const float32_t r_fuzz = 10.0F; - ASSERT_LT(r_fuzz, r_hull); - - std::vector hull; - - uint32_t hull_pts = 0U; - float32_t th = 0.0F; - // hull part 1 - for (uint32_t idx = 0U; idx < HULL_SIZE / 3U; ++idx) { - const auto pt = this->make(r_hull * cosf(th), r_hull * sinf(th), th); - hull.push_back(pt); - this->list.push_back(pt); - th = fmodf(th + dth, 2.0F * 3.14159F); - ++hull_pts; - } - - // fuzz part 1 - uint32_t fuzz_pts = 0U; - for (uint32_t idx = 0U; idx < FUZZ_SIZE / 2U; ++idx) { - const auto pt = this->make(r_fuzz * cosf(th), r_fuzz * sinf(th), th); - this->list.push_back(pt); - th = fmodf(th + dth, 2.0F * 3.14159F); - ++fuzz_pts; - } - - // hull part 2 - for (uint32_t idx = 0U; idx < HULL_SIZE / 3U; ++idx) { - const auto pt = this->make(r_hull * cosf(th), r_hull * sinf(th), th); - hull.push_back(pt); - this->list.push_back(pt); - th = fmodf(th + dth, 2.0F * 3.14159F); - ++hull_pts; - } - - // fuzz part 2 - for (uint32_t idx = 0U; idx < FUZZ_SIZE - fuzz_pts; ++idx) { - const auto pt = this->make(r_fuzz * cosf(th), r_fuzz * sinf(th), th); - this->list.push_back(pt); - th = fmodf(th + dth, 2.0F * 3.14159F); - } - - // hull part 3 - for (uint32_t idx = 0U; idx < HULL_SIZE - hull_pts; ++idx) { - const auto pt = this->make(r_hull * cosf(th), r_hull * sinf(th), th); - hull.push_back(pt); - this->list.push_back(pt); - th = fmodf(th + dth, 2.0F * 3.14159F); - } - - const auto last = this->convex_hull(); - - this->check_hull(last, hull); - ASSERT_EQ(std::distance(this->list.cbegin(), last), HULL_SIZE); -} - -TYPED_TEST(TypedConvexHullTest, Collinear) -{ - std::vector data( - {this->make(0, 0, 1), this->make(1, 0, 2), this->make(2, 0, 3), this->make(0, 2, 4), - this->make(1, 2, 8), this->make(2, 2, 7), this->make(1, 0, 6), this->make(1, 2, 5), - this->make(1, 1, 0)}); - const std::vector expect{{data[0], data[2], data[3], data[5]}}; - this->list.insert(this->list.begin(), data.begin(), data.end()); - - const auto last = this->convex_hull(); - - this->check_hull(last, expect); - ASSERT_EQ(std::distance(this->list.cbegin(), last), 4U); - - // check for order - auto it = this->list.begin(); - ASSERT_FLOAT_EQ(it->z, 1); - ++it; // node 1 - ASSERT_FLOAT_EQ(it->z, 3); - ++it; // node 1 - ASSERT_FLOAT_EQ(it->z, 7); - ++it; // node 2 - ASSERT_FLOAT_EQ(it->z, 4); - ++it; // node 3 - ASSERT_EQ(it, last); -} - -// degenerate cases -TYPED_TEST(TypedConvexHullTest, OverlappingPoints) -{ - std::vector data( - {this->make(3, -1, 1), this->make(4, -2, 2), this->make(5, -7, 3), this->make(4, -2, 4), - this->make(5, -7, 8), this->make(3, -1, 7), this->make(5, -7, 6), this->make(4, -2, 5), - this->make(3, -1, 0)}); - const std::vector expect{{data[0], data[1], data[2]}}; - this->list.insert(this->list.begin(), data.begin(), data.end()); - - const auto last = this->convex_hull(); - - ASSERT_EQ(std::distance(this->list.cbegin(), last), 3U); - this->check_hull(last, expect, false); -} - -TYPED_TEST(TypedConvexHullTest, Line) -{ - std::vector data( - {this->make(-3, 3, 1), this->make(-2, 2, 2), this->make(-1, 1, 3), this->make(-8, 8, 4), - this->make(-6, 6, 8), this->make(-4, 4, 7), this->make(-10, 10, 6), this->make(-12, 12, 5), - this->make(-11, 11, 0)}); - const std::vector expect{{data[2], data[7]}}; - this->list.insert(this->list.begin(), data.begin(), data.end()); - - const auto last = this->convex_hull(); - - ASSERT_EQ(std::distance(this->list.cbegin(), last), 2U); - this->check_hull(last, expect, false); - - // check for order: this part is a little loose - auto it = this->list.begin(); - ASSERT_FLOAT_EQ(it->z, 5); - ++it; // node 8 - ASSERT_FLOAT_EQ(it->z, 3); - ++it; // node 3 - ASSERT_EQ(it, last); -} - -/* -1 - 4 - - 3 - 2 -*/ -TYPED_TEST(TypedConvexHullTest, LowerHull) -{ - const std::vector data({ - this->make(1, 3, 1), - this->make(2, -2, 2), - this->make(3, -1, 3), - this->make(4, 1, 4), - }); - this->list.insert(this->list.begin(), data.begin(), data.end()); - - const auto last = this->convex_hull(); - - ASSERT_EQ(std::distance(this->list.cbegin(), last), 4U); - this->check_hull(last, data); - - // check for order: this part is a little loose - auto it = this->list.begin(); - ASSERT_FLOAT_EQ(it->z, 1); - ++it; - ASSERT_FLOAT_EQ(it->z, 2); - ++it; - ASSERT_FLOAT_EQ(it->z, 3); - ++it; - ASSERT_FLOAT_EQ(it->z, 4); - ++it; - ASSERT_EQ(it, last); -} - -// Ensure the leftmost item is properly shuffled -/* - 5 -1 6 - 2 4 - 3 -*/ -TYPED_TEST(TypedConvexHullTest, Root) -{ - const std::vector data({ - this->make(0, 0, 1), - this->make(1, -1, 2), - this->make(3, -2, 3), - this->make(4, 0, 4), - this->make(3, 1, 5), - this->make(1, 0, 6), - }); - const std::vector expect{{data[0], data[1], data[2], data[3], data[4]}}; - this->list.insert(this->list.begin(), data.begin(), data.end()); - - const auto last = this->convex_hull(); - - ASSERT_EQ(std::distance(this->list.cbegin(), last), 5); - this->check_hull(last, expect); - - auto it = this->list.begin(); - ASSERT_FLOAT_EQ(it->z, 1); - ++it; - ASSERT_FLOAT_EQ(it->z, 2); - ++it; - ASSERT_FLOAT_EQ(it->z, 3); - ++it; - ASSERT_FLOAT_EQ(it->z, 4); - ++it; - ASSERT_FLOAT_EQ(it->z, 5); - ++it; - ASSERT_EQ(it, last); - EXPECT_NE(last, this->list.cend()); - EXPECT_EQ(last->z, 6); -} - -// TODO(c.ho) random input, fuzzing, stress tests diff --git a/common/autoware_auto_geometry/test/src/test_geometry.cpp b/common/autoware_auto_geometry/test/src/test_geometry.cpp deleted file mode 100644 index 0a7dd288d0d79..0000000000000 --- a/common/autoware_auto_geometry/test/src/test_geometry.cpp +++ /dev/null @@ -1,25 +0,0 @@ -// Copyright 2018 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. -// -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. - -#include "gtest/gtest.h" -#include "test_bounding_box.hpp" -#include "test_spatial_hash.hpp" - -int32_t main(int32_t argc, char ** argv) -{ - ::testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/common/autoware_auto_geometry/test/src/test_hull_pockets.cpp b/common/autoware_auto_geometry/test/src/test_hull_pockets.cpp deleted file mode 100644 index 9477a83a488ed..0000000000000 --- a/common/autoware_auto_geometry/test/src/test_hull_pockets.cpp +++ /dev/null @@ -1,182 +0,0 @@ -// Copyright 2020 Embotech AG, Zurich, Switzerland. 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. -// -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. - -#include "autoware_auto_geometry/convex_hull.hpp" -#include "autoware_auto_geometry/hull_pockets.hpp" - -#include - -#include - -#include -#include -#include -#include - -using autoware::common::geometry::point_adapter::x_; -using autoware::common::geometry::point_adapter::y_; -using autoware::common::types::float32_t; -using autoware::common::types::float64_t; - -template -class TypedHullPocketsTest : public ::testing::Test -{ -protected: - PointT make(const float32_t x, const float32_t y, const float32_t z) - { - PointT ret; - ret.x = x; - ret.y = y; - ret.z = z; - return ret; - } -}; // class TypedHullPocketsTest - -using PointTypes = ::testing::Types; -// cppcheck-suppress syntaxError -TYPED_TEST_SUITE(TypedHullPocketsTest, PointTypes, ); -/// NOTE: This is the older version due to 1.8.0 of GTest. v1.8.1 uses TYPED_TEST_SUITE - -// Inner test function, shared among all the tests -template -typename std::vector::value_type>> -compute_hull_and_pockets(const Iter polygon_start, const Iter polygon_end) -{ - auto convex_hull_list = - std::list::value_type>{polygon_start, polygon_end}; - const auto cvx_hull_end = autoware::common::geometry::convex_hull(convex_hull_list); - - const typename decltype(convex_hull_list)::const_iterator list_beginning = - convex_hull_list.begin(); - const auto pockets = autoware::common::geometry::hull_pockets( - polygon_start, polygon_end, list_beginning, cvx_hull_end); - - return pockets; -} - -// Test for a triangle - any triangle should really not result in any pockets. -TYPED_TEST(TypedHullPocketsTest, Triangle) -{ - const auto polygon = std::vectormake(0, 0, 0))>{ - this->make(0, 0, 0), this->make(2, 0, 0), this->make(1, 1, 0)}; - - const auto pockets = compute_hull_and_pockets(polygon.begin(), polygon.end()); - ASSERT_EQ(pockets.size(), 0u); -} - -// Test for the use case: -// +--------------------+ -// | | -// | | -// | | -// | | -// | | -// | | -// +--------------------+ -// This should not result in any pockets. -TYPED_TEST(TypedHullPocketsTest, Box) -{ - const auto polygon = std::vectormake(0, 0, 0))>{ - this->make(0, 0, 0), this->make(2, 0, 0), this->make(2, 1, 0), this->make(0, 1, 0)}; - - const auto pockets = compute_hull_and_pockets(polygon.begin(), polygon.end()); - ASSERT_EQ(pockets.size(), 0u); -} - -// Test for the use case: -// +-----+ +-----+ -// / | | | -// / | | | -// + | | + -// | | | | -// | | | | -// | -------------- | -// | | -// | | -// | | -// | | -// +------------------------------+ -// This should come up with a single box on the top left. -TYPED_TEST(TypedHullPocketsTest, UShape) -{ - const auto polygon = std::vectormake(0, 0, 0))>{ - this->make(0, 0, 0), this->make(5, 0, 0), this->make(5, 4.5, 0), this->make(4, 5, 0), - this->make(4, 2, 0), this->make(2, 2, 0), this->make(2, 5, 0), this->make(0, 4.5, 0), - }; - - const auto pockets = compute_hull_and_pockets(polygon.begin(), polygon.end()); - - ASSERT_EQ(pockets.size(), 1u); - ASSERT_EQ(pockets[0].size(), 4u); - ASSERT_FLOAT_EQ(x_(pockets[0][0]), 4.0); - ASSERT_FLOAT_EQ(y_(pockets[0][0]), 5.0); - ASSERT_FLOAT_EQ(x_(pockets[0][1]), 4.0); - ASSERT_FLOAT_EQ(y_(pockets[0][1]), 2.0); -} - -// Test for the use case: -// +------+ -// | | -// | | -// | | -// +------------------+ +------+ -// | | -// | | -// | | -// +--------------------------------+ -// -// This should come up with two pockets, a triangle on the top left and one on the -// top right. -TYPED_TEST(TypedHullPocketsTest, TypicalGap) -{ - const auto polygon = std::vectormake(0, 0, 0))>{ - this->make(0, 0, 0), this->make(10, 0, 0), this->make(10, 2, 0), this->make(8, 2, 0), - this->make(8, 4, 0), this->make(6, 4, 0), this->make(6, 2, 0), this->make(0, 2, 0), - }; - - const auto pockets = compute_hull_and_pockets(polygon.begin(), polygon.end()); - - ASSERT_EQ(pockets.size(), 2u); - ASSERT_EQ(pockets[0].size(), 3u); - ASSERT_EQ(pockets[1].size(), 3u); - // TODO(s.me) check for correct pocket positioning -} - -// Test for the use case: -// -// +-----------------+ -// | | -// | | -// + | -// / | -// / | -// +-----------------+ -// -// This should come up with one pocket, in particular a pocket that contains -// the segment of the final to the first point. -TYPED_TEST(TypedHullPocketsTest, EndsInPocket) -{ - const auto polygon = std::vectormake(0, 0, 0))>{ - this->make(0, 0, 0), this->make(2, 0, 0), this->make(2, 2, 0), - this->make(0, 2, 0), this->make(0.1, 1, 0), - }; - - const auto pockets = compute_hull_and_pockets(polygon.begin(), polygon.end()); - - ASSERT_EQ(pockets.size(), 1u); - ASSERT_EQ(pockets[0].size(), 3u); - // TODO(s.me) check for correct pocket positioning -} diff --git a/common/autoware_auto_geometry/test/src/test_intersection.cpp b/common/autoware_auto_geometry/test/src/test_intersection.cpp deleted file mode 100644 index 1036c69573c49..0000000000000 --- a/common/autoware_auto_geometry/test/src/test_intersection.cpp +++ /dev/null @@ -1,155 +0,0 @@ -// Copyright 2021 Apex.AI, 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. - -// Co-developed by Tier IV, Inc. and Apex.AI, Inc. - -#include "autoware_auto_geometry/convex_hull.hpp" -#include "autoware_auto_geometry/intersection.hpp" - -#include - -#include - -struct TestPoint -{ - autoware::common::types::float32_t x; - autoware::common::types::float32_t y; -}; - -struct IntersectionTestParams -{ - std::list polygon1_pts; - std::list polygon2_pts; - std::list expected_intersection_pts; -}; - -void order_ccw(std::list & points) -{ - const auto end_it = autoware::common::geometry::convex_hull(points); - ASSERT_EQ(end_it, points.end()); // Points should have represent a shape -} - -class IntersectionTest : public ::testing::TestWithParam -{ -}; - -TEST_P(IntersectionTest, Basic) -{ - const auto get_ordered_polygon = [](auto polygon) { - order_ccw(polygon); - return polygon; - }; - - const auto polygon1 = get_ordered_polygon(GetParam().polygon1_pts); - const auto polygon2 = get_ordered_polygon(GetParam().polygon2_pts); - const auto expected_intersection = get_ordered_polygon(GetParam().expected_intersection_pts); - - const auto result = autoware::common::geometry::convex_polygon_intersection2d(polygon1, polygon2); - - ASSERT_EQ(result.size(), expected_intersection.size()); - auto expected_shape_it = expected_intersection.begin(); - for (auto result_it = result.begin(); result_it != result.end(); ++result_it) { - EXPECT_FLOAT_EQ(result_it->x, expected_shape_it->x); - EXPECT_FLOAT_EQ(result_it->y, expected_shape_it->y); - ++expected_shape_it; - } -} - -INSTANTIATE_TEST_SUITE_P( - Basic, IntersectionTest, - ::testing::Values( - IntersectionTestParams{{}, {}, {}}, - IntersectionTestParams{// Partial intersection - {{0.0F, 0.0F}, {10.0F, 0.0F}, {0.0F, 10.0F}, {10.0F, 10.0F}}, - {{5.0F, 5.0F}, {15.0F, 5.0F}, {5.0F, 15.0F}, {15.0F, 15.0F}}, - {{5.0F, 5.0F}, {10.0F, 5.0F}, {5.0F, 10.0F}, {10.0F, 10.0F}}}, - // Full intersection with overlapping edges - // TODO(yunus.caliskan): enable after #1231 - // IntersectionTestParams{ - // {{0.0F, 0.0F}, {10.0F, 0.0F}, {0.0F, 10.0F}, {10.0F, 10.0F}}, - // {{5.0F, 5.0F}, {10.0F, 5.0F}, {5.0F, 10.0F}, {10.0F, 10.0F}}, - // {{5.0F, 5.0F}, {10.0F, 5.0F}, {5.0F, 10.0F}, {10.0F, 10.0F}}, - // }, - IntersectionTestParams{ - // Fully contained - {{0.0F, 0.0F}, {10.0F, 0.0F}, {0.0F, 10.0F}, {10.0F, 10.0F}}, - {{5.0F, 5.0F}, {6.0F, 5.0F}, {5.0F, 7.0F}, {8.0F, 8.0F}}, - {{5.0F, 5.0F}, {6.0F, 5.0F}, {5.0F, 7.0F}, {8.0F, 8.0F}}, - }, - IntersectionTestParams{ - // Fully contained triangle - {{0.0F, 0.0F}, {10.0F, 0.0F}, {0.0F, 10.0F}, {10.0F, 10.0F}}, - {{5.0F, 5.0F}, {6.0F, 5.0F}, {5.0F, 7.0F}}, - {{5.0F, 5.0F}, {6.0F, 5.0F}, {5.0F, 7.0F}}, - }, - IntersectionTestParams{// Triangle rectangle intersection. - {{0.0F, 0.0F}, {10.0F, 0.0F}, {0.0F, 10.0F}, {10.0F, 10.0F}}, - {{5.0F, 1.0F}, {5.0F, 9.0F}, {15.0F, 5.0F}}, - {{5.0F, 1.0F}, {5.0F, 9.0F}, {10.0F, 3.0F}, {10.0F, 7.0F}}}, - IntersectionTestParams{// No intersection - {{0.0F, 0.0F}, {10.0F, 0.0F}, {0.0F, 10.0F}, {10.0F, 10.0F}}, - {{15.0F, 15.0F}, {20.0F, 15.0F}, {15.0F, 20.0F}, {20.0F, 20.0F}}, - {}} // cppcheck-suppress syntaxError - )); - -TEST(PolygonPointTest, Basic) -{ - GTEST_SKIP(); // TODO(yunus.caliskan): enable after #1231 - std::list polygon{{5.0F, 5.0F}, {10.0F, 5.0F}, {5.0F, 10.0F}, {10.0F, 10.0F}}; - order_ccw(polygon); - EXPECT_FALSE(autoware::common::geometry::is_point_inside_polygon_2d( - polygon.begin(), polygon.end(), TestPoint{0.0F, 10.0F})); -} - -// IoU of two intersecting shapes: a pentagon and a square. The test includes pen and paper -// computations for the intermediate steps as assertions. -TEST(IoUTest, PentagonRectangleIntersection) -{ - std::list polygon1{ - {0.0F, 3.0F}, {3.0F, 4.0F}, {6.0F, 3.0F}, {4.0F, 1.0F}, {2.0F, 1.0F}}; - std::list polygon2{{3.0F, 0.0F}, {3.0F, 2.0F}, {5.0F, 2.0F}, {5.0F, 0.0F}}; - - order_ccw(polygon1); - order_ccw(polygon2); - - const auto intersection = - autoware::common::geometry::convex_polygon_intersection2d(polygon1, polygon2); - const auto expected_intersection_area = - autoware::common::geometry::area_2d(intersection.begin(), intersection.end()); - ASSERT_FLOAT_EQ(expected_intersection_area, 1.5F); // Pen & paper proof. - - const auto expected_union_area = - autoware::common::geometry::area_2d(polygon1.begin(), polygon1.end()) + - autoware::common::geometry::area_2d(polygon2.begin(), polygon2.end()) - - expected_intersection_area; - ASSERT_FLOAT_EQ(expected_union_area, (11.0F + 4.0F - 1.5F)); // Pen & paper proof. - - const auto computed_iou = - autoware::common::geometry::convex_intersection_over_union_2d(polygon1, polygon2); - - EXPECT_FLOAT_EQ(computed_iou, expected_intersection_area / expected_union_area); -} - -// IoU of two non-intersecting rectangles. -TEST(IoUTest, NoIntersection) -{ - std::list polygon1{{0.0F, 0.0F}, {0.0F, 1.0F}, {1.0F, 1.0F}, {1.0F, 0.0F}}; - std::list polygon2{{3.0F, 0.0F}, {3.0F, 2.0F}, {5.0F, 2.0F}, {5.0F, 0.0F}}; - - order_ccw(polygon1); - order_ccw(polygon2); - - EXPECT_FLOAT_EQ( - autoware::common::geometry::convex_intersection_over_union_2d(polygon1, polygon2), 0.0F); -} diff --git a/common/autoware_auto_geometry/test/src/test_interval.cpp b/common/autoware_auto_geometry/test/src/test_interval.cpp deleted file mode 100644 index 266ab123f5203..0000000000000 --- a/common/autoware_auto_geometry/test/src/test_interval.cpp +++ /dev/null @@ -1,259 +0,0 @@ -// Copyright 2020 Mapless AI, Inc. -// -// 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. - -#include "autoware_auto_geometry/interval.hpp" - -#include - -#include -#include -#include - -using autoware::common::geometry::Interval; -using autoware::common::geometry::Interval_d; -using autoware::common::geometry::Interval_f; - -namespace -{ -const auto Inf = std::numeric_limits::infinity(); -const auto Min = std::numeric_limits::lowest(); -const auto Max = std::numeric_limits::max(); -const auto NaN = std::numeric_limits::quiet_NaN(); -const auto epsilon = 1e-5; -} // namespace - -//------------------------------------------------------------------------------ - -TEST(GeometryInterval, AbsEq) -{ - const auto i1 = Interval_d(-1.0, 1.0); - const auto i2 = Interval_d(-1.0 + 0.5 * epsilon, 1.0 + 0.5 * epsilon); - const auto shift = (2.0 * epsilon); - const auto i3 = Interval_d(-1.0 + shift, 1.0 + shift); - const auto i_empty = Interval_d(); - - EXPECT_TRUE(Interval_d::abs_eq(i1, i1, epsilon)); - EXPECT_TRUE(Interval_d::abs_eq(i1, i2, epsilon)); - EXPECT_TRUE(Interval_d::abs_eq(i2, i1, epsilon)); - EXPECT_FALSE(Interval_d::abs_eq(i1, i3, epsilon)); - EXPECT_FALSE(Interval_d::abs_eq(i3, i1, epsilon)); - EXPECT_FALSE(Interval_d::abs_eq(i1, i_empty, epsilon)); - EXPECT_FALSE(Interval_d::abs_eq(i_empty, i1, epsilon)); - EXPECT_TRUE(Interval_d::abs_eq(i_empty, i_empty, epsilon)); -} - -//------------------------------------------------------------------------------ - -TEST(GeometryInterval, IsSubsetEq) -{ - EXPECT_TRUE(Interval_d::is_subset_eq(Interval_d(-0.5, 0.5), Interval_d(-1.0, 1.0))); - EXPECT_TRUE(Interval_d::is_subset_eq(Interval_d(3.2, 4.2), Interval_d(3.2, 4.2))); - EXPECT_FALSE(Interval_d::is_subset_eq(Interval_d(-3.0, -1.0), Interval_d(1.0, 3.0))); - EXPECT_FALSE(Interval_d::is_subset_eq(Interval_d(1.0, 3.0), Interval_d(2.0, 4.0))); - EXPECT_FALSE(Interval_d::is_subset_eq(Interval_d(), Interval_d())); -} - -//------------------------------------------------------------------------------ - -TEST(GeometryInterval, ClampTo) -{ - const auto i = Interval_d(-1.0, 1.0); - { - const auto val = 0.0; - const auto p = Interval_d::clamp_to(i, val); - EXPECT_EQ(p, val); - } - - { - const auto val = -3.4; - const auto p = Interval_d::clamp_to(i, val); - EXPECT_EQ(p, Interval_d::min(i)); - } - - { - const auto val = 2.7; - const auto p = Interval_d::clamp_to(i, val); - EXPECT_EQ(p, Interval_d::max(i)); - } - - const auto val = 1.0; - const auto empty_interval = Interval_d(); - const auto projected = Interval_d::clamp_to(empty_interval, val); - EXPECT_TRUE(std::isnan(projected)); -} - -//------------------------------------------------------------------------------ - -TEST(GeometryInterval, Comparisons) -{ - { - const auto i1 = Interval_d(0.25, 1); - const auto i2 = Interval_d(0, 1); - EXPECT_FALSE((i1 == i2)); - EXPECT_TRUE((i1 != i2)); - } - - { - const auto i1 = Interval_d(-0.25, 0.5); - const auto i2 = Interval_d(0, 1); - EXPECT_FALSE((i1 == i2)); - EXPECT_TRUE((i1 != i2)); - } - - { - const auto i1 = Interval_d(0, 0.5); - const auto i2 = Interval_d(0, 1); - EXPECT_FALSE((i1 == i2)); - EXPECT_TRUE((i1 != i2)); - } - - { - const auto i1 = Interval_d(0, 1); - const auto i2 = Interval_d(0, 1); - EXPECT_TRUE((i1 == i2)); - EXPECT_FALSE((i1 != i2)); - } - - { - const auto i1 = Interval_d(0, 1); - const auto i2 = Interval_d(); - EXPECT_FALSE((i1 == i2)); - EXPECT_TRUE((i1 != i2)); - } - - { - const auto i1 = Interval_d(); - const auto i2 = Interval_d(); - EXPECT_TRUE((i1 == i2)); - EXPECT_FALSE((i1 != i2)); - } -} - -//------------------------------------------------------------------------------ - -TEST(GeometryInterval, Contains) -{ - { - const auto i = Interval_d(); - EXPECT_FALSE(Interval_d::contains(i, 0.0)); - } - - { - const auto i = Interval_d(-1.0, 1.0); - EXPECT_TRUE(Interval_d::contains(i, 0.0)); - EXPECT_FALSE(Interval_d::contains(i, 2.0)); - } -} - -//------------------------------------------------------------------------------ - -TEST(GeometryInterval, Empty) -{ - { - const auto i1 = Interval_d(); - const auto i2 = Interval_d(); - const auto i3 = Interval_d::intersect(i1, i2); - EXPECT_TRUE(Interval_d::empty(i3)); - } - - { - const auto i1 = Interval_d(); - const auto i2 = Interval_d(0.0, 1.0); - const auto i3 = Interval_d::intersect(i1, i2); - EXPECT_TRUE(Interval_d::empty(i3)); - } -} - -//------------------------------------------------------------------------------ - -TEST(GeometryInterval, ZeroMeasure) -{ - { - const auto i = Interval_d(0, 1); - EXPECT_FALSE(Interval_d::zero_measure(i)); - } - - { - const auto i = Interval_d(); - EXPECT_FALSE(Interval_d::zero_measure(i)); - } - - { - const auto i = Interval_d(2, 2); - EXPECT_TRUE(Interval_d::zero_measure(i)); - } -} - -//------------------------------------------------------------------------------ - -TEST(GeometryInterval, IntersectionMeasure) -{ - { - const auto i1 = Interval_d(-1.0, 1.0); - const auto i2 = Interval_d(-0.5, 1.5); - const auto i = Interval_d::intersect(i1, i2); - EXPECT_EQ(Interval_d::min(i), -0.5); - EXPECT_EQ(Interval_d::max(i), 1.0); - EXPECT_NEAR(Interval_d::measure(i), 1.5, epsilon); - } - - { - const auto i1 = Interval_d(-2.0, -1.0); - const auto i2 = Interval_d(1.0, 2.0); - const auto i = Interval_d::intersect(i1, i2); - EXPECT_TRUE(Interval_d::empty(i)); - EXPECT_TRUE(std::isnan(Interval_d::min(i))); - EXPECT_TRUE(std::isnan(Interval_d::max(i))); - EXPECT_TRUE(std::isnan(Interval_d::measure(i))); - } -} - -//------------------------------------------------------------------------------ - -TEST(GeometryInterval, ConstructionMeasure) -{ - { - const auto i = Interval_d(); - EXPECT_TRUE(std::isnan(Interval_d::min(i))); - EXPECT_TRUE(std::isnan(Interval_d::max(i))); - EXPECT_TRUE(std::isnan(Interval_d::measure(i))); - } - - { - const auto i = Interval_d(-1.0, 1.0); - EXPECT_EQ(Interval_d::min(i), -1.0); - EXPECT_EQ(Interval_d::max(i), 1.0); - EXPECT_NEAR(Interval_d::measure(i), 2.0, epsilon); - } - - { - const auto i = Interval_d(0.0, 0.0); - EXPECT_EQ(Interval_d::min(i), 0.0); - EXPECT_EQ(Interval_d::max(i), 0.0); - EXPECT_FALSE(Interval_d::empty(i)); - EXPECT_EQ(Interval_d::measure(i), 0.0); - } - - { - EXPECT_THROW({ Interval_d(1.0, -1.0); }, std::runtime_error); - } -} - -//------------------------------------------------------------------------------ diff --git a/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_detail.hpp b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_detail.hpp index 8c6ade475217a..4f545d194b2c2 100644 --- a/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_detail.hpp +++ b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_detail.hpp @@ -57,6 +57,9 @@ struct ObjectPropertyValues float alpha{0.999F}; }; +// Control object marker visualization +enum class ObjectFillType { Skeleton, Fill }; + // Map defining colors according to value of label field in ObjectClassification msg const std::map< autoware_auto_perception_msgs::msg::ObjectClassification::_label_type, ObjectPropertyValues> @@ -87,7 +90,8 @@ get_shape_marker_ptr( const autoware_auto_perception_msgs::msg::Shape & shape_msg, const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation, const std_msgs::msg::ColorRGBA & color_rgba, const double & line_width, - const bool & is_orientation_available = true); + const bool & is_orientation_available = true, + const ObjectFillType fill_type = ObjectFillType::Skeleton); AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC visualization_msgs::msg::Marker::SharedPtr get_2d_shape_marker_ptr( diff --git a/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp index 4290fdff49bb3..1093f6e4f2414 100644 --- a/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp +++ b/common/autoware_auto_perception_rviz_plugin/include/autoware_auto_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp @@ -112,6 +112,12 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase m_confidence_interval_property->addOption("95%", 2); m_confidence_interval_property->addOption("99%", 3); + m_object_fill_type_property = new rviz_common::properties::EnumProperty( + "Object Fill Type", "skeleton", "Change object fill type in visualization", this); + m_object_fill_type_property->addOption( + "skeleton", static_cast(detail::ObjectFillType::Skeleton)); + m_object_fill_type_property->addOption("Fill", static_cast(detail::ObjectFillType::Fill)); + // iterate over default values to create and initialize the properties. for (const auto & map_property_it : detail::kDefaultObjectPropertyValues) { const auto & class_property_values = map_property_it.second; @@ -189,9 +195,13 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase const bool & is_orientation_available) const { const std_msgs::msg::ColorRGBA color_rgba = get_color_rgba(labels); + const auto fill_type = + static_cast(m_object_fill_type_property->getOptionInt()); + if (m_display_type_property->getOptionInt() == 0) { return detail::get_shape_marker_ptr( - shape_msg, centroid, orientation, color_rgba, line_width, is_orientation_available); + shape_msg, centroid, orientation, color_rgba, line_width, is_orientation_available, + fill_type); } else if (m_display_type_property->getOptionInt() == 1) { return detail::get_2d_shape_marker_ptr( shape_msg, centroid, orientation, color_rgba, line_width, is_orientation_available); @@ -526,6 +536,8 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase rviz_common::properties::EnumProperty * m_simple_visualize_mode_property; // Property to set confidence interval of state estimations rviz_common::properties::EnumProperty * m_confidence_interval_property; + // Property to set visualization type + rviz_common::properties::EnumProperty * m_object_fill_type_property; // Property to enable/disable label visualization rviz_common::properties::BoolProperty m_display_label_property; // Property to enable/disable uuid visualization diff --git a/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp b/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp index 8be9d1c01332e..7631acffafdf9 100644 --- a/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp +++ b/common/autoware_auto_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp @@ -495,23 +495,37 @@ visualization_msgs::msg::Marker::SharedPtr get_shape_marker_ptr( const autoware_auto_perception_msgs::msg::Shape & shape_msg, const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation, const std_msgs::msg::ColorRGBA & color_rgba, const double & line_width, - const bool & is_orientation_available) + const bool & is_orientation_available, const ObjectFillType fill_type) { auto marker_ptr = std::make_shared(); marker_ptr->ns = std::string("shape"); + marker_ptr->color = color_rgba; + marker_ptr->scale.x = line_width; using autoware_auto_perception_msgs::msg::Shape; if (shape_msg.type == Shape::BOUNDING_BOX) { - marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST; - calc_bounding_box_line_list(shape_msg, marker_ptr->points); + if (fill_type == ObjectFillType::Skeleton) { + marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST; + calc_bounding_box_line_list(shape_msg, marker_ptr->points); + } else if (fill_type == ObjectFillType::Fill) { + marker_ptr->type = visualization_msgs::msg::Marker::CUBE; + marker_ptr->scale = shape_msg.dimensions; + marker_ptr->color.a = 0.75f; + } if (is_orientation_available) { calc_bounding_box_direction_line_list(shape_msg, marker_ptr->points); } else { calc_bounding_box_orientation_line_list(shape_msg, marker_ptr->points); } } else if (shape_msg.type == Shape::CYLINDER) { - marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST; - calc_cylinder_line_list(shape_msg, marker_ptr->points); + if (fill_type == ObjectFillType::Skeleton) { + marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST; + calc_cylinder_line_list(shape_msg, marker_ptr->points); + } else if (fill_type == ObjectFillType::Fill) { + marker_ptr->type = visualization_msgs::msg::Marker::CYLINDER; + marker_ptr->scale = shape_msg.dimensions; + marker_ptr->color.a = 0.75f; + } } else if (shape_msg.type == Shape::POLYGON) { marker_ptr->type = visualization_msgs::msg::Marker::LINE_LIST; calc_polygon_line_list(shape_msg, marker_ptr->points); @@ -523,8 +537,6 @@ visualization_msgs::msg::Marker::SharedPtr get_shape_marker_ptr( marker_ptr->action = visualization_msgs::msg::Marker::MODIFY; marker_ptr->pose = to_pose(centroid, orientation); marker_ptr->lifetime = rclcpp::Duration::from_seconds(0.15); - marker_ptr->scale.x = line_width; - marker_ptr->color = color_rgba; return marker_ptr; } 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 0000000000000..f7f5db1249511 Binary files /dev/null and b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/av_timer.png differ diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/LICENSE b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/LICENSE new file mode 100644 index 0000000000000..cc04d393573f0 --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/LICENSE @@ -0,0 +1,93 @@ +Copyright 2011 The Quicksand Project Authors (https://github.com/andrew-paglinawan/QuicksandFamily), with Reserved Font Name “Quicksand”. + +This Font Software is licensed under the SIL Open Font License, Version 1.1. +This license is copied below, and is also available with a FAQ at: +http://scripts.sil.org/OFL + + +----------------------------------------------------------- +SIL OPEN FONT LICENSE Version 1.1 - 26 February 2007 +----------------------------------------------------------- + +PREAMBLE +The goals of the Open Font License (OFL) are to stimulate worldwide +development of collaborative font projects, to support the font creation +efforts of academic and linguistic communities, and to provide a free and +open framework in which fonts may be shared and improved in partnership +with others. + +The OFL allows the licensed fonts to be used, studied, modified and +redistributed freely as long as they are not sold by themselves. The +fonts, including any derivative works, can be bundled, embedded, +redistributed and/or sold with any software provided that any reserved +names are not used by derivative works. The fonts and derivatives, +however, cannot be released under any other type of license. The +requirement for fonts to remain under this license does not apply +to any document created using the fonts or their derivatives. + +DEFINITIONS +"Font Software" refers to the set of files released by the Copyright +Holder(s) under this license and clearly marked as such. This may +include source files, build scripts and documentation. + +"Reserved Font Name" refers to any names specified as such after the +copyright statement(s). + +"Original Version" refers to the collection of Font Software components as +distributed by the Copyright Holder(s). + +"Modified Version" refers to any derivative made by adding to, deleting, +or substituting -- in part or in whole -- any of the components of the +Original Version, by changing formats or by porting the Font Software to a +new environment. + +"Author" refers to any designer, engineer, programmer, technical +writer or other person who contributed to the Font Software. + +PERMISSION & CONDITIONS +Permission is hereby granted, free of charge, to any person obtaining +a copy of the Font Software, to use, study, copy, merge, embed, modify, +redistribute, and sell modified and unmodified copies of the Font +Software, subject to the following conditions: + +1) Neither the Font Software nor any of its individual components, +in Original or Modified Versions, may be sold by itself. + +2) Original or Modified Versions of the Font Software may be bundled, +redistributed and/or sold with any software, provided that each copy +contains the above copyright notice and this license. These can be +included either as stand-alone text files, human-readable headers or +in the appropriate machine-readable metadata fields within text or +binary files as long as those fields can be easily viewed by the user. + +3) No Modified Version of the Font Software may use the Reserved Font +Name(s) unless explicit written permission is granted by the corresponding +Copyright Holder. This restriction only applies to the primary font name as +presented to the users. + +4) The name(s) of the Copyright Holder(s) or the Author(s) of the Font +Software shall not be used to promote, endorse or advertise any +Modified Version, except to acknowledge the contribution(s) of the +Copyright Holder(s) and the Author(s) or with their explicit written +permission. + +5) The Font Software, modified or unmodified, in part or in whole, +must be distributed entirely under this license, and must not be +distributed under any other license. The requirement for fonts to +remain under this license does not apply to any document created +using the Font Software. + +TERMINATION +This license becomes null and void if any of the above conditions are +not met. + +DISCLAIMER +THE FONT SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, +EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO ANY WARRANTIES OF +MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT +OF COPYRIGHT, PATENT, TRADEMARK, OR OTHER RIGHT. IN NO EVENT SHALL THE +COPYRIGHT HOLDER BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, +INCLUDING ANY GENERAL, SPECIAL, INDIRECT, INCIDENTAL, OR CONSEQUENTIAL +DAMAGES, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING +FROM, OUT OF THE USE OR INABILITY TO USE THE FONT SOFTWARE OR FROM +OTHER DEALINGS IN THE FONT SOFTWARE. diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Bold.ttf b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Bold.ttf new file mode 100644 index 0000000000000..07d5127c04b17 Binary files /dev/null and b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Bold.ttf differ 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 0000000000000..60323ed6abdf1 Binary files /dev/null and b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Regular.ttf differ diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/path.png b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/path.png new file mode 100644 index 0000000000000..62af338b8c053 Binary files /dev/null and b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/path.png differ diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin-extras.cmake b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin-extras.cmake new file mode 100644 index 0000000000000..9d6f156555e57 --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin-extras.cmake @@ -0,0 +1,31 @@ +# Copyright (c) 2021, Open Source Robotics Foundation, 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 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. + +# find package Qt5 because otherwise using the rviz_default_plugins::rviz_default_plugins +# exported target will complain that the Qt5::Widgets target does not exist +find_package(Qt5 REQUIRED QUIET COMPONENTS Widgets) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp new file mode 100644 index 0000000000000..ab5abfe3c3d83 --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp @@ -0,0 +1,83 @@ +// 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 MISSION_DETAILS_DISPLAY_HPP_ +#define MISSION_DETAILS_DISPLAY_HPP_ +#ifndef Q_MOC_RUN +#include "overlay_utils.hpp" +#include "remaining_distance_time_display.hpp" + +#include +#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/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/include/signal_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/signal_display.hpp index 4fa39f2c5a903..ec1acb9a5dc68 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/signal_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/signal_display.hpp @@ -102,7 +102,7 @@ private Q_SLOTS: turn_signals_sub_; rclcpp::Subscription::SharedPtr hazard_lights_sub_; - rclcpp::Subscription::SharedPtr traffic_sub_; + rclcpp::Subscription::SharedPtr traffic_sub_; rclcpp::Subscription::SharedPtr speed_limit_sub_; std::mutex property_mutex_; @@ -117,7 +117,7 @@ private Q_SLOTS: const autoware_auto_vehicle_msgs::msg::HazardLightsReport::ConstSharedPtr & msg); void updateSpeedLimitData(const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg); void updateTrafficLightData( - const autoware_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr msg); + const autoware_perception_msgs::msg::TrafficSignal::ConstSharedPtr msg); void drawWidget(QImage & hud); }; } // namespace autoware_overlay_rviz_plugin diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/traffic_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/traffic_display.hpp index 20410a78edc44..efa30f37ccb3e 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/traffic_display.hpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/traffic_display.hpp @@ -24,7 +24,6 @@ #include #include -#include #include #include @@ -40,8 +39,8 @@ class TrafficDisplay TrafficDisplay(); void drawTrafficLightIndicator(QPainter & painter, const QRectF & backgroundRect); void updateTrafficLightData( - const autoware_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr & msg); - autoware_perception_msgs::msg::TrafficSignalArray current_traffic_; + const autoware_perception_msgs::msg::TrafficSignal::ConstSharedPtr & msg); + autoware_perception_msgs::msg::TrafficSignal current_traffic_; private: QImage traffic_light_image_; 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/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/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/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 b2995327eb472..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 @@ -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( @@ -111,67 +111,22 @@ void SignalDisplay::onInitialize() speed_limit_topic_property_->initialize(rviz_ros_node); traffic_topic_property_ = std::make_unique( - "Traffic Topic", "/perception/traffic_light_recognition/traffic_signals", - "autoware_perception/msgs/msg/TrafficSignalArray", "Topic for Traffic Light Data", this, + "Traffic Topic", + "/planning/scenario_planning/lane_driving/behavior_planning/debug/traffic_signal", + "autoware_perception/msgs/msg/TrafficSignal", "Topic for Traffic Light Data", this, SLOT(topic_updated_traffic())); traffic_topic_property_->initialize(rviz_ros_node); } 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::TrafficSignalArray::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() @@ -237,7 +192,7 @@ void SignalDisplay::onDisable() } void SignalDisplay::updateTrafficLightData( - const autoware_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr msg) + const autoware_perception_msgs::msg::TrafficSignal::ConstSharedPtr msg) { std::lock_guard lock(property_mutex_); @@ -324,16 +279,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); } @@ -341,18 +298,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(); @@ -363,8 +314,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); @@ -403,7 +354,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(); } @@ -420,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); }); @@ -434,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); }); @@ -448,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); }); @@ -463,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); }); @@ -478,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); }); @@ -494,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); }); @@ -506,14 +454,12 @@ void SignalDisplay::topic_updated_traffic() // resubscribe to the topic traffic_sub_.reset(); 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(), - [this](const autoware_perception_msgs::msg::TrafficSignalArray::SharedPtr msg) { - updateTrafficLightData(msg); - }); + traffic_sub_ = rviz_ros_node->get_raw_node() + ->create_subscription( + traffic_topic_property_->getTopicStd(), rclcpp::QoS(rclcpp::KeepLast(10)), + [this](const autoware_perception_msgs::msg::TrafficSignal::SharedPtr msg) { + updateTrafficLightData(msg); + }); } } // namespace autoware_overlay_rviz_plugin 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 4fea8f78b80da..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 @@ -48,7 +48,7 @@ TrafficDisplay::TrafficDisplay() } void TrafficDisplay::updateTrafficLightData( - const autoware_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr & msg) + const autoware_perception_msgs::msg::TrafficSignal::ConstSharedPtr & msg) { current_traffic_ = *msg; } @@ -62,16 +62,14 @@ 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_.signals.empty()) { - switch (current_traffic_.signals[0].elements[0].color) { + if (!current_traffic_.elements.empty()) { + switch (current_traffic_.elements[0].color) { case 1: painter.setBrush(QBrush(tl_red_)); painter.drawEllipse(circleRect); @@ -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 || diff --git a/common/autoware_point_types/README.md b/common/autoware_point_types/README.md new file mode 100644 index 0000000000000..92f19d2bc353a --- /dev/null +++ b/common/autoware_point_types/README.md @@ -0,0 +1 @@ +# Autoware Point Types diff --git a/common/component_interface_specs/include/component_interface_specs/localization.hpp b/common/component_interface_specs/include/component_interface_specs/localization.hpp index 70c590c837927..e00d8cef1840d 100644 --- a/common/component_interface_specs/include/component_interface_specs/localization.hpp +++ b/common/component_interface_specs/include/component_interface_specs/localization.hpp @@ -18,16 +18,16 @@ #include #include -#include #include #include +#include namespace localization_interface { struct Initialize { - using Service = autoware_adapi_v1_msgs::srv::InitializeLocalization; + using Service = tier4_localization_msgs::srv::InitializeLocalization; static constexpr char name[] = "/localization/initialize"; }; diff --git a/common/component_interface_specs/package.xml b/common/component_interface_specs/package.xml index 1ad5f410a814a..13f135c925258 100644 --- a/common/component_interface_specs/package.xml +++ b/common/component_interface_specs/package.xml @@ -21,6 +21,7 @@ rclcpp rosidl_runtime_cpp tier4_control_msgs + tier4_localization_msgs tier4_map_msgs tier4_planning_msgs tier4_system_msgs 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; 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/common/mission_planner_rviz_plugin/CMakeLists.txt b/common/mission_planner_rviz_plugin/CMakeLists.txt deleted file mode 100644 index 2b06e6db3e70d..0000000000000 --- a/common/mission_planner_rviz_plugin/CMakeLists.txt +++ /dev/null @@ -1,23 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(mission_planner_rviz_plugin) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -find_package(Qt5 REQUIRED Core Widgets) -set(QT_LIBRARIES Qt5::Widgets) -set(CMAKE_AUTOMOC ON) -set(CMAKE_INCLUDE_CURRENT_DIR ON) - -ament_auto_add_library(${PROJECT_NAME} SHARED - src/mrm_goal.cpp - src/route_selector_panel.cpp -) - -target_link_libraries(${PROJECT_NAME} - ${QT_LIBRARIES} -) - -pluginlib_export_plugin_description_file(rviz_common plugins/plugin_description.xml) - -ament_auto_package() diff --git a/common/mission_planner_rviz_plugin/README.md b/common/mission_planner_rviz_plugin/README.md deleted file mode 100644 index 59d36a0a2f840..0000000000000 --- a/common/mission_planner_rviz_plugin/README.md +++ /dev/null @@ -1,18 +0,0 @@ -# mission_planner_rviz_plugin - -## MrmGoalTool - -This is a copy of `rviz_default_plugins::tools::GoalTool`. Used together with the RouteSelectorPanel to set the MRM route. -After adding the tool, change the topic name to `/rviz/route_selector/mrm/goal` from the topic property panel in rviz. - -## RouteSelectorPanel - -This panel shows the main and mrm route state in the route_selector and the route states in the mission_planner. -Additionally, it provides clear and set functions for each main route and mrm route. - -| Trigger | Action | -| -------------------------------------- | ------------------------------------------------------------------------ | -| main route clear button | call `/planning/mission_planning/route_selector/main/clear_route` | -| mrm route clear button | call `/planning/mission_planning/route_selector/mrm/clear_route` | -| `/rviz/route_selector/main/goal` topic | call `/planning/mission_planning/route_selector/main/set_waypoint_route` | -| `/rviz/route_selector/mrm/goal` topic | call `/planning/mission_planning/route_selector/mrm/set_waypoint_route` | diff --git a/common/mission_planner_rviz_plugin/package.xml b/common/mission_planner_rviz_plugin/package.xml deleted file mode 100644 index e45cf2739f260..0000000000000 --- a/common/mission_planner_rviz_plugin/package.xml +++ /dev/null @@ -1,29 +0,0 @@ - - - - mission_planner_rviz_plugin - 0.0.0 - The mission_planner_rviz_plugin package - Takagi, Isamu - Apache License 2.0 - - ament_cmake_auto - autoware_cmake - - geometry_msgs - libqt5-core - libqt5-gui - libqt5-widgets - rclcpp - rviz_common - rviz_default_plugins - tier4_planning_msgs - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - - diff --git a/common/mission_planner_rviz_plugin/plugins/plugin_description.xml b/common/mission_planner_rviz_plugin/plugins/plugin_description.xml deleted file mode 100644 index c8285fcc604d7..0000000000000 --- a/common/mission_planner_rviz_plugin/plugins/plugin_description.xml +++ /dev/null @@ -1,8 +0,0 @@ - - - MrmGoalTool - - - RouteSelectorPanel - - diff --git a/common/mission_planner_rviz_plugin/src/route_selector_panel.cpp b/common/mission_planner_rviz_plugin/src/route_selector_panel.cpp deleted file mode 100644 index b4b376b1e76ec..0000000000000 --- a/common/mission_planner_rviz_plugin/src/route_selector_panel.cpp +++ /dev/null @@ -1,148 +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. - -#include "route_selector_panel.hpp" - -#include -#include - -#include -#include - -namespace rviz_plugins -{ - -QString to_string_state(const RouteState & state) -{ - // clang-format off - switch (state.state) { - case RouteState::UNKNOWN: return "unknown"; - case RouteState::INITIALIZING: return "initializing"; - case RouteState::UNSET: return "unset"; - case RouteState::ROUTING: return "routing"; - case RouteState::SET: return "set"; - case RouteState::REROUTING: return "rerouting"; - case RouteState::ARRIVED: return "arrived"; - case RouteState::ABORTED: return "aborted"; - case RouteState::INTERRUPTED: return "interrupted"; - default: return "-----"; - } - // clang-format on -} - -RouteSelectorPanel::RouteSelectorPanel(QWidget * parent) : rviz_common::Panel(parent) -{ - main_state_ = new QLabel("unknown"); - main_clear_ = new QPushButton("clear"); - mrm_state_ = new QLabel("unknown"); - mrm_clear_ = new QPushButton("clear"); - planner_state_ = new QLabel("unknown"); - - connect(main_clear_, &QPushButton::clicked, this, &RouteSelectorPanel::onMainClear); - connect(mrm_clear_, &QPushButton::clicked, this, &RouteSelectorPanel::onMrmClear); - - const auto layout = new QGridLayout(); - setLayout(layout); - layout->addWidget(new QLabel("main"), 0, 0); - layout->addWidget(main_state_, 0, 1); - layout->addWidget(main_clear_, 0, 2); - layout->addWidget(new QLabel("mrm"), 1, 0); - layout->addWidget(mrm_state_, 1, 1); - layout->addWidget(mrm_clear_, 1, 2); - layout->addWidget(new QLabel("planner"), 2, 0); - layout->addWidget(planner_state_, 2, 1); -} - -void RouteSelectorPanel::onInitialize() -{ - auto lock = getDisplayContext()->getRosNodeAbstraction().lock(); - auto node = lock->get_raw_node(); - - const auto durable_qos = rclcpp::QoS(1).transient_local(); - - sub_main_goal_ = node->create_subscription( - "/rviz/route_selector/main/goal", rclcpp::QoS(1), - std::bind(&RouteSelectorPanel::onMainGoal, this, std::placeholders::_1)); - sub_mrm_goal_ = node->create_subscription( - "/rviz/route_selector/mrm/goal", rclcpp::QoS(1), - std::bind(&RouteSelectorPanel::onMrmGoal, this, std::placeholders::_1)); - sub_main_state_ = node->create_subscription( - "/planning/mission_planning/route_selector/main/state", durable_qos, - std::bind(&RouteSelectorPanel::onMainState, this, std::placeholders::_1)); - sub_mrm_state_ = node->create_subscription( - "/planning/mission_planning/route_selector/mrm/state", durable_qos, - std::bind(&RouteSelectorPanel::onMrmState, this, std::placeholders::_1)); - sub_planner_state_ = node->create_subscription( - "/planning/mission_planning/state", durable_qos, - std::bind(&RouteSelectorPanel::onPlannerState, this, std::placeholders::_1)); - - cli_main_clear_ = - node->create_client("/planning/mission_planning/route_selector/main/clear_route"); - cli_mrm_clear_ = - node->create_client("/planning/mission_planning/route_selector/mrm/clear_route"); - cli_main_set_waypoint_ = node->create_client( - "/planning/mission_planning/route_selector/main/set_waypoint_route"); - cli_mrm_set_waypoint_ = node->create_client( - "/planning/mission_planning/route_selector/mrm/set_waypoint_route"); -} - -void RouteSelectorPanel::onMainGoal(const PoseStamped::ConstSharedPtr msg) -{ - const auto req = std::make_shared(); - req->header = msg->header; - req->goal_pose = msg->pose; - req->allow_modification = true; - cli_main_set_waypoint_->async_send_request(req); -} - -void RouteSelectorPanel::onMrmGoal(const PoseStamped::ConstSharedPtr msg) -{ - const auto req = std::make_shared(); - req->header = msg->header; - req->goal_pose = msg->pose; - req->allow_modification = true; - cli_mrm_set_waypoint_->async_send_request(req); -} - -void RouteSelectorPanel::onMainState(RouteState::ConstSharedPtr msg) -{ - main_state_->setText(to_string_state(*msg)); -} - -void RouteSelectorPanel::onMrmState(RouteState::ConstSharedPtr msg) -{ - mrm_state_->setText(to_string_state(*msg)); -} - -void RouteSelectorPanel::onPlannerState(RouteState::ConstSharedPtr msg) -{ - planner_state_->setText(to_string_state(*msg)); -} - -void RouteSelectorPanel::onMainClear() -{ - const auto req = std::make_shared(); - cli_main_clear_->async_send_request(req); -} - -void RouteSelectorPanel::onMrmClear() -{ - const auto req = std::make_shared(); - cli_mrm_clear_->async_send_request(req); -} - -} // namespace rviz_plugins - -#include -PLUGINLIB_EXPORT_CLASS(rviz_plugins::RouteSelectorPanel, rviz_common::Panel) diff --git a/common/mission_planner_rviz_plugin/src/route_selector_panel.hpp b/common/mission_planner_rviz_plugin/src/route_selector_panel.hpp deleted file mode 100644 index 99101730661e0..0000000000000 --- a/common/mission_planner_rviz_plugin/src/route_selector_panel.hpp +++ /dev/null @@ -1,75 +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. - -#ifndef ROUTE_SELECTOR_PANEL_HPP_ -#define ROUTE_SELECTOR_PANEL_HPP_ - -#include -#include -#include -#include - -#include -#include -#include -#include - -namespace rviz_plugins -{ - -using geometry_msgs::msg::PoseStamped; -using tier4_planning_msgs::msg::RouteState; -using tier4_planning_msgs::srv::ClearRoute; -using tier4_planning_msgs::srv::SetWaypointRoute; - -class RouteSelectorPanel : public rviz_common::Panel -{ - Q_OBJECT - -public: - explicit RouteSelectorPanel(QWidget * parent = nullptr); - void onInitialize() override; - -private: - QLabel * main_state_; - QLabel * mrm_state_; - QLabel * planner_state_; - QPushButton * main_clear_; - QPushButton * mrm_clear_; - - rclcpp::Subscription::SharedPtr sub_main_goal_; - rclcpp::Subscription::SharedPtr sub_mrm_goal_; - void onMainGoal(const PoseStamped::ConstSharedPtr msg); - void onMrmGoal(const PoseStamped::ConstSharedPtr msg); - - rclcpp::Subscription::SharedPtr sub_main_state_; - rclcpp::Subscription::SharedPtr sub_mrm_state_; - rclcpp::Subscription::SharedPtr sub_planner_state_; - void onMainState(RouteState::ConstSharedPtr msg); - void onMrmState(RouteState::ConstSharedPtr msg); - void onPlannerState(RouteState::ConstSharedPtr msg); - - rclcpp::Client::SharedPtr cli_main_clear_; - rclcpp::Client::SharedPtr cli_mrm_clear_; - rclcpp::Client::SharedPtr cli_main_set_waypoint_; - rclcpp::Client::SharedPtr cli_mrm_set_waypoint_; - -private Q_SLOTS: - void onMainClear(); - void onMrmClear(); -}; - -} // namespace rviz_plugins - -#endif // ROUTE_SELECTOR_PANEL_HPP_ 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 56% 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..077c66f9dd6bc 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,47 +13,42 @@ // 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 #include -#include #include #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; } + template void set( - const std::vector & points, - const Pose & curr_pose, const Pose & stop_pose, const VelocityFactorStatus status, - const std::string detail = ""); + const std::vector & points, const Pose & curr_pose, const Pose & stop_pose, + const VelocityFactorStatus status, 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/include/motion_utils/resample/resample_utils.hpp b/common/motion_utils/include/motion_utils/resample/resample_utils.hpp index 8bb5f13e3fb78..fb151ec56b085 100644 --- a/common/motion_utils/include/motion_utils/resample/resample_utils.hpp +++ b/common/motion_utils/include/motion_utils/resample/resample_utils.hpp @@ -27,7 +27,11 @@ namespace resample_utils { constexpr double close_s_threshold = 1e-6; -#define log_error(message) std::cerr << "\033[31m " << message << " \033[0m" << std::endl; +static inline rclcpp::Logger get_logger() +{ + constexpr const char * logger{"motion_utils.resample_utils"}; + return rclcpp::get_logger(logger); +} template bool validate_size(const T & points) @@ -62,27 +66,27 @@ bool validate_arguments(const T & input_points, const std::vector & resa { // Check size of the arguments if (!validate_size(input_points)) { - log_error("[resample_utils] invalid argument: The number of input points is less than 2"); + RCLCPP_DEBUG(get_logger(), "invalid argument: The number of input points is less than 2"); tier4_autoware_utils::print_backtrace(); return false; } if (!validate_size(resampling_intervals)) { - log_error( - "[resample_utils] invalid argument: The number of resampling intervals is less than 2"); + RCLCPP_DEBUG( + get_logger(), "invalid argument: The number of resampling intervals is less than 2"); tier4_autoware_utils::print_backtrace(); return false; } // Check resampling range if (!validate_resampling_range(input_points, resampling_intervals)) { - log_error("[resample_utils] invalid argument: resampling interval is longer than input points"); + RCLCPP_DEBUG(get_logger(), "invalid argument: resampling interval is longer than input points"); tier4_autoware_utils::print_backtrace(); return false; } // Check duplication if (!validate_points_duplication(input_points)) { - log_error("[resample_utils] invalid argument: input points has some duplicated points"); + RCLCPP_DEBUG(get_logger(), "invalid argument: input points has some duplicated points"); tier4_autoware_utils::print_backtrace(); return false; } @@ -95,23 +99,23 @@ bool validate_arguments(const T & input_points, const double resampling_interval { // Check size of the arguments if (!validate_size(input_points)) { - log_error("[resample_utils] invalid argument: The number of input points is less than 2"); + RCLCPP_DEBUG(get_logger(), "invalid argument: The number of input points is less than 2"); tier4_autoware_utils::print_backtrace(); return false; } // check resampling interval if (resampling_interval < motion_utils::overlap_threshold) { - log_error( - "[resample_utils] invalid argument: resampling interval is less than " + - std::to_string(motion_utils::overlap_threshold)); + RCLCPP_DEBUG( + get_logger(), "invalid argument: resampling interval is less than %f", + motion_utils::overlap_threshold); tier4_autoware_utils::print_backtrace(); return false; } // Check duplication if (!validate_points_duplication(input_points)) { - log_error("[resample_utils] invalid argument: input points has some duplicated points"); + RCLCPP_DEBUG(get_logger(), "invalid argument: input points has some duplicated points"); tier4_autoware_utils::print_backtrace(); return false; } diff --git a/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp b/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp index 7c9b5a5378ab6..7e2d92c9434fb 100644 --- a/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp +++ b/common/motion_utils/include/motion_utils/trajectory/trajectory.hpp @@ -21,6 +21,7 @@ #include "tier4_autoware_utils/system/backtrace.hpp" #include +#include #include #include @@ -33,9 +34,14 @@ #include #include #include + namespace motion_utils { -#define log_error(message) std::cerr << "\033[31m " << message << " \033[0m" << std::endl; +static inline rclcpp::Logger get_logger() +{ + constexpr const char * logger{"motion_utils.trajectory"}; + return rclcpp::get_logger(logger); +} /** * @brief validate if points container is empty or not @@ -216,7 +222,7 @@ std::optional searchZeroVelocityIndex( try { validateNonEmpty(points_with_twist); } catch (const std::exception & e) { - log_error(e.what()); + RCLCPP_DEBUG(get_logger(), "%s", e.what()); return {}; } @@ -248,7 +254,7 @@ std::optional searchZeroVelocityIndex(const T & points_with_twist, const try { validateNonEmpty(points_with_twist); } catch (const std::exception & e) { - log_error(e.what()); + RCLCPP_DEBUG(get_logger(), "%s", e.what()); return {}; } @@ -338,7 +344,7 @@ std::optional findNearestIndex( try { validateNonEmpty(points); } catch (const std::exception & e) { - log_error(e.what()); + RCLCPP_DEBUG(get_logger(), "%s", e.what()); return {}; } @@ -411,9 +417,10 @@ double calcLongitudinalOffsetToSegment( if (throw_exception) { throw std::out_of_range(error_message); } - log_error( - error_message + - " Return NaN since no_throw option is enabled. The maintainer must check the code."); + RCLCPP_DEBUG( + get_logger(), + "%s Return NaN since no_throw option is enabled. The maintainer must check the code.", + error_message.c_str()); return std::nan(""); } @@ -425,7 +432,7 @@ double calcLongitudinalOffsetToSegment( try { validateNonEmpty(overlap_removed_points); } catch (const std::exception & e) { - log_error(e.what()); + RCLCPP_DEBUG(get_logger(), "%s", e.what()); return std::nan(""); } } @@ -438,9 +445,10 @@ double calcLongitudinalOffsetToSegment( if (throw_exception) { throw std::runtime_error(error_message); } - log_error( - error_message + - " Return NaN since no_throw option is enabled. The maintainer must check the code."); + RCLCPP_DEBUG( + get_logger(), + "%s Return NaN since no_throw option is enabled. The maintainer must check the code.", + error_message.c_str()); return std::nan(""); } @@ -586,9 +594,10 @@ double calcLateralOffset( try { validateNonEmpty(overlap_removed_points); } catch (const std::exception & e) { - log_error( - std::string(e.what()) + - " Return NaN since no_throw option is enabled. The maintainer must check the code."); + RCLCPP_DEBUG( + get_logger(), + "%s Return NaN since no_throw option is enabled. The maintainer must check the code.", + e.what()); return std::nan(""); } } @@ -601,9 +610,10 @@ double calcLateralOffset( if (throw_exception) { throw std::runtime_error(error_message); } - log_error( - error_message + - " Return NaN since no_throw option is enabled. The maintainer must check the code."); + RCLCPP_DEBUG( + get_logger(), + "%s Return NaN since no_throw option is enabled. The maintainer must check the code.", + error_message.c_str()); return std::nan(""); } @@ -658,9 +668,10 @@ double calcLateralOffset( try { validateNonEmpty(overlap_removed_points); } catch (const std::exception & e) { - log_error( - std::string(e.what()) + - " Return NaN since no_throw option is enabled. The maintainer must check the code."); + RCLCPP_DEBUG( + get_logger(), + "%s Return NaN since no_throw option is enabled. The maintainer must check the code.", + e.what()); return std::nan(""); } } @@ -673,9 +684,10 @@ double calcLateralOffset( if (throw_exception) { throw std::runtime_error(error_message); } - log_error( - error_message + - " Return NaN since no_throw option is enabled. The maintainer must check the code."); + RCLCPP_DEBUG( + get_logger(), + "%s Return NaN since no_throw option is enabled. The maintainer must check the code.", + error_message.c_str()); return std::nan(""); } @@ -711,7 +723,7 @@ double calcSignedArcLength(const T & points, const size_t src_idx, const size_t try { validateNonEmpty(points); } catch (const std::exception & e) { - log_error(e.what()); + RCLCPP_DEBUG(get_logger(), "%s", e.what()); return 0.0; } @@ -754,7 +766,7 @@ std::vector calcSignedArcLengthPartialSum( try { validateNonEmpty(points); } catch (const std::exception & e) { - log_error(e.what()); + RCLCPP_DEBUG(get_logger(), "%s", e.what()); return {}; } @@ -806,7 +818,7 @@ double calcSignedArcLength( try { validateNonEmpty(points); } catch (const std::exception & e) { - log_error(e.what()); + RCLCPP_DEBUG(get_logger(), "%s", e.what()); return 0.0; } @@ -849,7 +861,7 @@ double calcSignedArcLength( try { validateNonEmpty(points); } catch (const std::exception & e) { - log_error(e.what()); + RCLCPP_DEBUG(get_logger(), "%s", e.what()); return 0.0; } @@ -888,7 +900,7 @@ double calcSignedArcLength( try { validateNonEmpty(points); } catch (const std::exception & e) { - log_error(e.what()); + RCLCPP_DEBUG(get_logger(), "%s", e.what()); return 0.0; } @@ -928,7 +940,7 @@ double calcArcLength(const T & points) try { validateNonEmpty(points); } catch (const std::exception & e) { - log_error(e.what()); + RCLCPP_DEBUG(get_logger(), "%s", e.what()); return 0.0; } @@ -1037,7 +1049,7 @@ std::optional calcDistanceToForwardStopPoint( try { validateNonEmpty(points_with_twist); } catch (const std::exception & e) { - log_error(e.what()); + RCLCPP_DEBUG(get_logger(), "%s", e.what()); return {}; } @@ -1071,7 +1083,7 @@ std::optional calcLongitudinalOffsetPoint( try { validateNonEmpty(points); } catch (const std::exception & e) { - log_error(e.what()); + RCLCPP_DEBUG(get_logger(), "%s", e.what()); return {}; } @@ -1084,9 +1096,10 @@ std::optional calcLongitudinalOffsetPoint( if (throw_exception) { throw std::out_of_range(error_message); } - log_error( - error_message + - " Return NaN since no_throw option is enabled. The maintainer must check the code."); + RCLCPP_DEBUG( + get_logger(), + "%s Return NaN since no_throw option is enabled. The maintainer must check the code.", + error_message.c_str()); return {}; } @@ -1153,7 +1166,7 @@ std::optional calcLongitudinalOffsetPoint( try { validateNonEmpty(points); } catch (const std::exception & e) { - log_error("Failed to calculate longitudinal offset: " + std::string(e.what())); + RCLCPP_DEBUG(get_logger(), "Failed to calculate longitudinal offset: %s", e.what()); return {}; } @@ -1201,7 +1214,7 @@ std::optional calcLongitudinalOffsetPose( try { validateNonEmpty(points); } catch (const std::exception & e) { - log_error("Failed to calculate longitudinal offset: " + std::string(e.what())); + RCLCPP_DEBUG(get_logger(), "Failed to calculate longitudinal offset: %s", e.what()); return {}; } @@ -1214,12 +1227,12 @@ std::optional calcLongitudinalOffsetPose( if (throw_exception) { throw std::out_of_range(error_message); } - log_error(error_message); + RCLCPP_DEBUG(get_logger(), "%s", error_message.c_str()); return {}; } if (points.size() == 1) { - log_error("Failed to calculate longitudinal offset: points size is one."); + RCLCPP_DEBUG(get_logger(), "Failed to calculate longitudinal offset: points size is one."); return {}; } @@ -1304,7 +1317,7 @@ std::optional calcLongitudinalOffsetPose( try { validateNonEmpty(points); } catch (const std::exception & e) { - log_error(e.what()); + RCLCPP_DEBUG(get_logger(), "%s", e.what()); return {}; } @@ -1350,7 +1363,7 @@ std::optional insertTargetPoint( try { validateNonEmpty(points); } catch (const std::exception & e) { - log_error(e.what()); + RCLCPP_DEBUG(get_logger(), "%s", e.what()); return {}; } @@ -1365,7 +1378,7 @@ std::optional insertTargetPoint( try { validateNonSharpAngle(p_front, p_target, p_back); } catch (const std::exception & e) { - log_error(e.what()); + RCLCPP_DEBUG(get_logger(), "%s", e.what()); return {}; } @@ -1908,20 +1921,21 @@ insertOrientation * radians (default: M_PI_2) */ template -void removeInvalidOrientationPoints(T & points, const double max_yaw_diff = M_PI_2) +void removeFirstInvalidOrientationPoints(T & points, const double max_yaw_diff = M_PI_2) { - for (size_t i = 1; i < points.size();) { - const auto p1 = tier4_autoware_utils::getPose(points.at(i - 1)); - const auto p2 = tier4_autoware_utils::getPose(points.at(i)); + for (auto itr = points.begin(); std::next(itr) != points.end();) { + const auto p1 = tier4_autoware_utils::getPose(*itr); + const auto p2 = tier4_autoware_utils::getPose(*std::next(itr)); const double yaw1 = tf2::getYaw(p1.orientation); const double yaw2 = tf2::getYaw(p2.orientation); if ( max_yaw_diff < std::abs(tier4_autoware_utils::normalizeRadian(yaw1 - yaw2)) || !tier4_autoware_utils::isDrivingForward(p1, p2)) { - points.erase(points.begin() + i); + points.erase(std::next(itr)); + return; } else { - ++i; + itr++; } } } @@ -2231,7 +2245,7 @@ std::optional calcDistanceToForwardStopPoint( try { validateNonEmpty(points_with_twist); } catch (const std::exception & e) { - log_error("Failed to calculate stop distance" + std::string(e.what())); + RCLCPP_DEBUG(get_logger(), "Failed to calculate stop distance %s", e.what()); return {}; } @@ -2370,7 +2384,7 @@ T cropPoints( cropped_forward_points, target_pos, modified_target_seg_idx, backward_length); if (cropped_points.size() < 2) { - log_error("Return original points since cropped_points size is less than 2."); + RCLCPP_DEBUG(get_logger(), "Return original points since cropped_points size is less than 2."); return points; } @@ -2415,7 +2429,7 @@ double calcYawDeviation( try { validateNonEmpty(overlap_removed_points); } catch (const std::exception & e) { - log_error(e.what()); + RCLCPP_DEBUG(get_logger(), "%s", e.what()); return 0.0; } } @@ -2428,9 +2442,10 @@ double calcYawDeviation( if (throw_exception) { throw std::runtime_error(error_message); } - log_error( - error_message + - " Return 0 since no_throw option is enabled. The maintainer must check the code."); + RCLCPP_DEBUG( + get_logger(), + "%s Return 0 since no_throw option is enabled. The maintainer must check the code.", + error_message.c_str()); return 0.0; } 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/common/motion_utils/src/factor/velocity_factor_interface.cpp b/common/motion_utils/src/factor/velocity_factor_interface.cpp new file mode 100644 index 0000000000000..20742af0b6c0c --- /dev/null +++ b/common/motion_utils/src/factor/velocity_factor_interface.cpp @@ -0,0 +1,49 @@ +// 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. +// 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 +#include + +namespace motion_utils +{ +template +void VelocityFactorInterface::set( + const std::vector & points, const Pose & curr_pose, const Pose & stop_pose, + const VelocityFactorStatus status, 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 = + static_cast(motion_utils::calcSignedArcLength(points, curr_point, stop_point)); + velocity_factor_.status = status; + velocity_factor_.detail = detail; +} + +template void VelocityFactorInterface::set( + const std::vector &, const Pose &, + const Pose &, const VelocityFactorStatus, const std::string &); +template void VelocityFactorInterface::set( + const std::vector &, const Pose &, const Pose &, + const VelocityFactorStatus, const std::string &); +template void VelocityFactorInterface::set( + const std::vector &, const Pose &, + const Pose &, const VelocityFactorStatus, const std::string &); + +} // namespace motion_utils diff --git a/common/motion_utils/test/src/trajectory/test_trajectory.cpp b/common/motion_utils/test/src/trajectory/test_trajectory.cpp index eb6a06041e65d..8e84b111b0688 100644 --- a/common/motion_utils/test/src/trajectory/test_trajectory.cpp +++ b/common/motion_utils/test/src/trajectory/test_trajectory.cpp @@ -1876,40 +1876,34 @@ TEST(trajectory, insertTargetPoint) // Invalid target point(In front of begin point) { - testing::internal::CaptureStderr(); auto traj_out = traj; const auto p_target = createPoint(-1.0, 0.0, 0.0); const size_t base_idx = findNearestSegmentIndex(traj.points, p_target); const auto insert_idx = insertTargetPoint(base_idx, p_target, traj_out.points); - EXPECT_NE(testing::internal::GetCapturedStderr().find("sharp angle"), std::string::npos); EXPECT_EQ(insert_idx, std::nullopt); } // Invalid target point(Behind of end point) { - testing::internal::CaptureStderr(); auto traj_out = traj; const auto p_target = createPoint(10.0, 0.0, 0.0); const size_t base_idx = findNearestSegmentIndex(traj.points, p_target); const auto insert_idx = insertTargetPoint(base_idx, p_target, traj_out.points); - EXPECT_NE(testing::internal::GetCapturedStderr().find("sharp angle"), std::string::npos); EXPECT_EQ(insert_idx, std::nullopt); } // Invalid target point(Huge lateral offset) { - testing::internal::CaptureStderr(); auto traj_out = traj; const auto p_target = createPoint(4.0, 10.0, 0.0); const size_t base_idx = findNearestSegmentIndex(traj.points, p_target); const auto insert_idx = insertTargetPoint(base_idx, p_target, traj_out.points); - EXPECT_NE(testing::internal::GetCapturedStderr().find("sharp angle"), std::string::npos); EXPECT_EQ(insert_idx, std::nullopt); } @@ -2304,13 +2298,11 @@ TEST(trajectory, insertTargetPoint_Length) // Invalid target point(Huge lateral offset) { - testing::internal::CaptureStderr(); auto traj_out = traj; const auto p_target = createPoint(4.0, 10.0, 0.0); const auto insert_idx = insertTargetPoint(4.0, p_target, traj_out.points); - EXPECT_NE(testing::internal::GetCapturedStderr().find("sharp angle."), std::string::npos); EXPECT_EQ(insert_idx, std::nullopt); } @@ -4310,40 +4302,34 @@ TEST(trajectory, insertStopPoint_with_pose_and_segment_index) // Invalid target point(In front of begin point) { - testing::internal::CaptureStderr(); auto traj_out = traj; const auto p_target = createPoint(-1.0, 0.0, 0.0); const size_t base_idx = findNearestSegmentIndex(traj.points, p_target); const auto insert_idx = insertStopPoint(base_idx, p_target, traj_out.points); - EXPECT_NE(testing::internal::GetCapturedStderr().find("sharp angle."), std::string::npos); EXPECT_EQ(insert_idx, std::nullopt); } // Invalid target point(Behind of end point) { - testing::internal::CaptureStderr(); auto traj_out = traj; const auto p_target = createPoint(10.0, 0.0, 0.0); const size_t base_idx = findNearestSegmentIndex(traj.points, p_target); const auto insert_idx = insertStopPoint(base_idx, p_target, traj_out.points); - EXPECT_NE(testing::internal::GetCapturedStderr().find("sharp angle."), std::string::npos); EXPECT_EQ(insert_idx, std::nullopt); } // Invalid target point(Huge lateral offset) { - testing::internal::CaptureStderr(); auto traj_out = traj; const auto p_target = createPoint(4.0, 10.0, 0.0); const size_t base_idx = findNearestSegmentIndex(traj.points, p_target); const auto insert_idx = insertStopPoint(base_idx, p_target, traj_out.points); - EXPECT_NE(testing::internal::GetCapturedStderr().find("sharp angle."), std::string::npos); EXPECT_EQ(insert_idx, std::nullopt); } @@ -5351,10 +5337,10 @@ TEST(trajectory, cropPoints) } } -TEST(Trajectory, removeInvalidOrientationPoints) +TEST(Trajectory, removeFirstInvalidOrientationPoints) { using motion_utils::insertOrientation; - using motion_utils::removeInvalidOrientationPoints; + using motion_utils::removeFirstInvalidOrientationPoints; const double max_yaw_diff = M_PI_2; @@ -5365,7 +5351,7 @@ TEST(Trajectory, removeInvalidOrientationPoints) auto modified_traj = traj; insertOrientation(modified_traj.points, true); modifyTrajectory(modified_traj); - removeInvalidOrientationPoints(modified_traj.points, max_yaw_diff); + removeFirstInvalidOrientationPoints(modified_traj.points, max_yaw_diff); EXPECT_EQ(modified_traj.points.size(), expected_size); for (size_t i = 0; i < modified_traj.points.size() - 1; ++i) { EXPECT_EQ(traj.points.at(i), modified_traj.points.at(i)); @@ -5388,7 +5374,7 @@ TEST(Trajectory, removeInvalidOrientationPoints) [&](Trajectory & t) { auto invalid_point = t.points.back(); invalid_point.pose.orientation = - tf2::toMsg(tf2::Quaternion(tf2::Vector3(0, 0, 1), 3 * M_PI_2)); + tf2::toMsg(tf2::Quaternion(tf2::Vector3(0, 0, 1), 3 * M_PI_4)); t.points.push_back(invalid_point); }, traj.points.size()); @@ -5399,21 +5385,10 @@ TEST(Trajectory, removeInvalidOrientationPoints) [&](Trajectory & t) { auto invalid_point = t.points[4]; invalid_point.pose.orientation = - tf2::toMsg(tf2::Quaternion(tf2::Vector3(0, 0, 1), 3 * M_PI_2)); + tf2::toMsg(tf2::Quaternion(tf2::Vector3(0, 0, 1), 3 * M_PI_4)); t.points.insert(t.points.begin() + 4, invalid_point); }, traj.points.size()); - - // invalid point at the beginning - testRemoveInvalidOrientationPoints( - traj, - [&](Trajectory & t) { - auto invalid_point = t.points.front(); - invalid_point.pose.orientation = - tf2::toMsg(tf2::Quaternion(tf2::Vector3(0, 0, 1), 3 * M_PI_2)); - t.points.insert(t.points.begin(), invalid_point); - }, - 1); // expected size is 1 since only the first point remains } TEST(trajectory, calcYawDeviation) diff --git a/common/rtc_manager_rviz_plugin/CMakeLists.txt b/common/rtc_manager_rviz_plugin/CMakeLists.txt deleted file mode 100644 index f2fad9e24665f..0000000000000 --- a/common/rtc_manager_rviz_plugin/CMakeLists.txt +++ /dev/null @@ -1,28 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(rtc_manager_rviz_plugin) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -find_package(Qt5 REQUIRED Core Widgets) -set(QT_LIBRARIES Qt5::Widgets) -set(CMAKE_AUTOMOC ON) -set(CMAKE_INCLUDE_CURRENT_DIR ON) -add_definitions(-DQT_NO_KEYWORDS) - -ament_auto_add_library(${PROJECT_NAME} SHARED - src/rtc_manager_panel.cpp -) - -target_link_libraries(${PROJECT_NAME} - ${QT_LIBRARIES} -) - -# 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/common/rtc_manager_rviz_plugin/README.md b/common/rtc_manager_rviz_plugin/README.md deleted file mode 100644 index 7a15d56fe235a..0000000000000 --- a/common/rtc_manager_rviz_plugin/README.md +++ /dev/null @@ -1,36 +0,0 @@ -# rtc_manager_rviz_plugin - -## Purpose - -The purpose of this Rviz plugin is - -1. To display each content of RTC status. - -2. To switch each module of RTC auto mode. - -3. To change RTC cooperate commands by button. - -![rtc_manager_panel](./images/rtc_manager_panel.png) - -## Inputs / Outputs - -### Input - -| Name | Type | Description | -| ------------------------------ | ------------------------------------------- | --------------------------------------- | -| `/api/external/get/rtc_status` | `tier4_rtc_msgs::msg::CooperateStatusArray` | The statuses of each Cooperate Commands | - -### Output - -| Name | Type | Description | -| -------------------------------- | ---------------------------------------- | ---------------------------------------------------- | -| `/api/external/set/rtc_commands` | `tier4_rtc_msgs::src::CooperateCommands` | The Cooperate Commands for each planning | -| `/planning/enable_auto_mode/*` | `tier4_rtc_msgs::src::AutoMode` | The Cooperate Commands mode for each planning module | - -## HowToUse - -1. Start rviz and select panels/Add new panel. - ![select_panel](./images/select_panels.png) - -2. tier4_state_rviz_plugin/RTCManagerPanel and press OK. - ![select_rtc_panel](./images/rtc_selection.png) diff --git a/common/rtc_manager_rviz_plugin/icons/classes/RTCManagerPanel.png b/common/rtc_manager_rviz_plugin/icons/classes/RTCManagerPanel.png deleted file mode 100644 index 6a67573717ae1..0000000000000 Binary files a/common/rtc_manager_rviz_plugin/icons/classes/RTCManagerPanel.png and /dev/null differ diff --git a/common/rtc_manager_rviz_plugin/images/rtc_manager_panel.png b/common/rtc_manager_rviz_plugin/images/rtc_manager_panel.png deleted file mode 100644 index 36c1b4760308b..0000000000000 Binary files a/common/rtc_manager_rviz_plugin/images/rtc_manager_panel.png and /dev/null differ diff --git a/common/rtc_manager_rviz_plugin/images/rtc_selection.png b/common/rtc_manager_rviz_plugin/images/rtc_selection.png deleted file mode 100644 index f9c5d120bdd70..0000000000000 Binary files a/common/rtc_manager_rviz_plugin/images/rtc_selection.png and /dev/null differ diff --git a/common/rtc_manager_rviz_plugin/images/select_panels.png b/common/rtc_manager_rviz_plugin/images/select_panels.png deleted file mode 100644 index a691602c42c3c..0000000000000 Binary files a/common/rtc_manager_rviz_plugin/images/select_panels.png and /dev/null differ diff --git a/common/rtc_manager_rviz_plugin/package.xml b/common/rtc_manager_rviz_plugin/package.xml deleted file mode 100644 index 53f00386bdb4d..0000000000000 --- a/common/rtc_manager_rviz_plugin/package.xml +++ /dev/null @@ -1,33 +0,0 @@ - - - - rtc_manager_rviz_plugin - 0.0.0 - The rtc manager rviz plugin package - Taiki Tanaka - Tomoya Kimura - - Apache License 2.0 - - ament_cmake_auto - autoware_cmake - - libqt5-core - libqt5-gui - libqt5-widgets - qtbase5-dev - rclcpp - rviz_common - tier4_external_api_msgs - tier4_planning_msgs - tier4_rtc_msgs - unique_identifier_msgs - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - - diff --git a/common/rtc_manager_rviz_plugin/plugins/plugin_description.xml b/common/rtc_manager_rviz_plugin/plugins/plugin_description.xml deleted file mode 100644 index 001ae153e6762..0000000000000 --- a/common/rtc_manager_rviz_plugin/plugins/plugin_description.xml +++ /dev/null @@ -1,9 +0,0 @@ - - - - RTCManagerPanel - - - diff --git a/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.cpp b/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.cpp deleted file mode 100644 index 058a5d5deb5d6..0000000000000 --- a/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.cpp +++ /dev/null @@ -1,474 +0,0 @@ -// -// Copyright 2020 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 "rtc_manager_panel.hpp" - -#include -#include -#include -#include - -#include - -namespace rviz_plugins -{ -inline std::string Bool2String(const bool var) -{ - return var ? "True" : "False"; -} -inline bool uint2bool(uint8_t var) -{ - return var == static_cast(0) ? false : true; -} -using std::placeholders::_1; -using std::placeholders::_2; - -std::string getModuleName(const uint8_t module_type) -{ - switch (module_type) { - case Module::LANE_CHANGE_LEFT: { - return "lane_change_left"; - } - case Module::LANE_CHANGE_RIGHT: { - return "lane_change_right"; - } - case Module::EXT_REQUEST_LANE_CHANGE_LEFT: { - return "external_request_lane_change_left"; - } - case Module::EXT_REQUEST_LANE_CHANGE_RIGHT: { - return "external_request_lane_change_right"; - } - case Module::AVOIDANCE_BY_LC_LEFT: { - return "avoidance_by_lane_change_left"; - } - case Module::AVOIDANCE_BY_LC_RIGHT: { - return "avoidance_by_lane_change_right"; - } - case Module::AVOIDANCE_LEFT: { - return "avoidance_left"; - } - case Module::AVOIDANCE_RIGHT: { - return "avoidance_right"; - } - case Module::GOAL_PLANNER: { - return "goal_planner"; - } - case Module::START_PLANNER: { - return "start_planner"; - } - case Module::TRAFFIC_LIGHT: { - return "traffic_light"; - } - case Module::INTERSECTION: { - return "intersection"; - } - case Module::CROSSWALK: { - return "crosswalk"; - } - case Module::BLIND_SPOT: { - return "blind_spot"; - } - case Module::DETECTION_AREA: { - return "detection_area"; - } - case Module::NO_STOPPING_AREA: { - return "no_stopping_area"; - } - case Module::OCCLUSION_SPOT: { - return "occlusion_spot"; - } - case Module::INTERSECTION_OCCLUSION: { - return "intersection_occlusion"; - } - } - return "NONE"; -} - -bool isPathChangeModule(const uint8_t module_type) -{ - if ( - module_type == Module::LANE_CHANGE_LEFT || module_type == Module::LANE_CHANGE_RIGHT || - module_type == Module::EXT_REQUEST_LANE_CHANGE_LEFT || - module_type == Module::EXT_REQUEST_LANE_CHANGE_RIGHT || - module_type == Module::AVOIDANCE_BY_LC_LEFT || module_type == Module::AVOIDANCE_BY_LC_RIGHT || - module_type == Module::AVOIDANCE_LEFT || module_type == Module::AVOIDANCE_RIGHT || - module_type == Module::GOAL_PLANNER || module_type == Module::START_PLANNER) { - return true; - } - return false; -} - -RTCManagerPanel::RTCManagerPanel(QWidget * parent) : rviz_common::Panel(parent) -{ - // TODO(tanaka): replace this magic number to Module::SIZE - const size_t module_size = 19; - auto_modes_.reserve(module_size); - auto * v_layout = new QVBoxLayout; - auto vertical_header = new QHeaderView(Qt::Vertical); - vertical_header->hide(); - auto horizontal_header = new QHeaderView(Qt::Horizontal); - horizontal_header->setSectionResizeMode(QHeaderView::Stretch); - auto_mode_table_ = new QTableWidget(); - auto_mode_table_->setColumnCount(4); - auto_mode_table_->setHorizontalHeaderLabels( - {"Module", "ToAutoMode", "ToManualMode", "ApprovalMode"}); - auto_mode_table_->setVerticalHeader(vertical_header); - auto_mode_table_->setHorizontalHeader(horizontal_header); - const size_t num_modules = module_size; - auto_mode_table_->setRowCount(num_modules); - for (size_t i = 0; i < num_modules; i++) { - auto * rtc_auto_mode = new RTCAutoMode(); - rtc_auto_mode->setParent(this); - // module - { - const uint8_t module_type = static_cast(i); - rtc_auto_mode->module_name = getModuleName(module_type); - std::string module_name = rtc_auto_mode->module_name; - auto label = new QLabel(QString::fromStdString(module_name)); - label->setAlignment(Qt::AlignCenter); - label->setText(QString::fromStdString(module_name)); - if (isPathChangeModule(module_type)) - label->setStyleSheet(BG_PURPLE); - else - label->setStyleSheet(BG_ORANGE); - auto_mode_table_->setCellWidget(i, 0, label); - } - // mode button - { - // auto mode button - rtc_auto_mode->auto_module_button_ptr = new QPushButton("auto mode"); - rtc_auto_mode->auto_module_button_ptr->setCheckable(true); - connect( - rtc_auto_mode->auto_module_button_ptr, &QPushButton::clicked, rtc_auto_mode, - &RTCAutoMode::onChangeToAutoMode); - auto_mode_table_->setCellWidget(i, 1, rtc_auto_mode->auto_module_button_ptr); - // manual mode button - rtc_auto_mode->manual_module_button_ptr = new QPushButton("manual mode"); - rtc_auto_mode->manual_module_button_ptr->setCheckable(true); - connect( - rtc_auto_mode->manual_module_button_ptr, &QPushButton::clicked, rtc_auto_mode, - &RTCAutoMode::onChangeToManualMode); - auto_mode_table_->setCellWidget(i, 2, rtc_auto_mode->manual_module_button_ptr); - } - // current mode - { - QString mode = QString::fromStdString("INIT"); - rtc_auto_mode->auto_manual_mode_label = new QLabel(mode); - rtc_auto_mode->auto_manual_mode_label->setAlignment(Qt::AlignCenter); - rtc_auto_mode->auto_manual_mode_label->setText(mode); - auto_mode_table_->setCellWidget(i, 3, rtc_auto_mode->auto_manual_mode_label); - } - auto_modes_.emplace_back(rtc_auto_mode); - } - v_layout->addWidget(auto_mode_table_); - - num_rtc_status_ptr_ = new QLabel("Init"); - v_layout->addWidget(num_rtc_status_ptr_); - - // lateral execution - auto * exe_path_change_layout = new QHBoxLayout; - { - exec_path_change_button_ptr_ = new QPushButton("Execute Path Change"); - exec_path_change_button_ptr_->setCheckable(false); - exec_path_change_button_ptr_->setStyleSheet(BG_PURPLE); - connect( - exec_path_change_button_ptr_, &QPushButton::clicked, this, - &RTCManagerPanel::onClickExecutePathChange); - exe_path_change_layout->addWidget(exec_path_change_button_ptr_); - wait_path_change_button_ptr_ = new QPushButton("Wait Path Change"); - wait_path_change_button_ptr_->setCheckable(false); - wait_path_change_button_ptr_->setStyleSheet(BG_PURPLE); - connect( - wait_path_change_button_ptr_, &QPushButton::clicked, this, - &RTCManagerPanel::onClickWaitPathChange); - exe_path_change_layout->addWidget(wait_path_change_button_ptr_); - } - v_layout->addLayout(exe_path_change_layout); - - // longitudinal execution - auto * exe_vel_change_layout = new QHBoxLayout; - { - exec_vel_change_button_ptr_ = new QPushButton("Execute Velocity Change"); - exec_vel_change_button_ptr_->setCheckable(false); - exec_vel_change_button_ptr_->setStyleSheet(BG_ORANGE); - connect( - exec_vel_change_button_ptr_, &QPushButton::clicked, this, - &RTCManagerPanel::onClickExecuteVelChange); - exe_vel_change_layout->addWidget(exec_vel_change_button_ptr_); - wait_vel_change_button_ptr_ = new QPushButton("Wait Velocity Change"); - wait_vel_change_button_ptr_->setCheckable(false); - wait_vel_change_button_ptr_->setStyleSheet(BG_ORANGE); - connect( - wait_vel_change_button_ptr_, &QPushButton::clicked, this, - &RTCManagerPanel::onClickWaitVelChange); - exe_vel_change_layout->addWidget(wait_vel_change_button_ptr_); - } - v_layout->addLayout(exe_vel_change_layout); - - // execution - auto * rtc_exe_layout = new QHBoxLayout; - { - exec_button_ptr_ = new QPushButton("Execute All"); - exec_button_ptr_->setCheckable(false); - connect(exec_button_ptr_, &QPushButton::clicked, this, &RTCManagerPanel::onClickExecution); - rtc_exe_layout->addWidget(exec_button_ptr_); - wait_button_ptr_ = new QPushButton("Wait All"); - wait_button_ptr_->setCheckable(false); - connect(wait_button_ptr_, &QPushButton::clicked, this, &RTCManagerPanel::onClickWait); - rtc_exe_layout->addWidget(wait_button_ptr_); - } - v_layout->addLayout(rtc_exe_layout); - - // statuses - auto * rtc_table_layout = new QHBoxLayout; - { - auto vertical_header = new QHeaderView(Qt::Vertical); - vertical_header->hide(); - auto horizontal_header = new QHeaderView(Qt::Horizontal); - horizontal_header->setSectionResizeMode(QHeaderView::Stretch); - rtc_table_ = new QTableWidget(); - rtc_table_->setColumnCount(column_size_); - rtc_table_->setHorizontalHeaderLabels( - {"ID", "Module", "AW Safe", "Received Cmd", "AutoMode", "StartDistance", "FinishDistance"}); - rtc_table_->setVerticalHeader(vertical_header); - rtc_table_->setHorizontalHeader(horizontal_header); - rtc_table_layout->addWidget(rtc_table_); - v_layout->addLayout(rtc_table_layout); - } - setLayout(v_layout); -} - -void RTCManagerPanel::onInitialize() -{ - raw_node_ = this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); - - client_rtc_commands_ = - raw_node_->create_client("/api/external/set/rtc_commands"); - - for (size_t i = 0; i < auto_modes_.size(); i++) { - auto & a = auto_modes_.at(i); - // auto mode - a->enable_auto_mode_cli = - raw_node_->create_client(enable_auto_mode_namespace_ + "/" + a->module_name); - } - - sub_rtc_status_ = raw_node_->create_subscription( - "/api/external/get/rtc_status", 1, std::bind(&RTCManagerPanel::onRTCStatus, this, _1)); -} - -void RTCAutoMode::onChangeToAutoMode() -{ - AutoMode::Request::SharedPtr request = std::make_shared(); - request->enable = true; - enable_auto_mode_cli->async_send_request(request); - auto_manual_mode_label->setText("AutoMode"); - auto_manual_mode_label->setStyleSheet(BG_BLUE); - auto_module_button_ptr->setChecked(true); - manual_module_button_ptr->setChecked(false); -} - -void RTCAutoMode::onChangeToManualMode() -{ - AutoMode::Request::SharedPtr request = std::make_shared(); - request->enable = false; - enable_auto_mode_cli->async_send_request(request); - auto_manual_mode_label->setText("ManualMode"); - auto_manual_mode_label->setStyleSheet(BG_YELLOW); - manual_module_button_ptr->setChecked(true); - auto_module_button_ptr->setChecked(false); -} - -CooperateCommand setRTCCommandFromStatus(CooperateStatus & status) -{ - CooperateCommand cooperate_command; - cooperate_command.uuid = status.uuid; - cooperate_command.module = status.module; - cooperate_command.command = status.command_status; - return cooperate_command; -} - -void RTCManagerPanel::onClickChangeRequest(const bool is_path_change, const uint8_t command) -{ - if (!cooperate_statuses_ptr_) return; - if (cooperate_statuses_ptr_->statuses.empty()) return; - auto executable_cooperate_commands_request = std::make_shared(); - executable_cooperate_commands_request->stamp = cooperate_statuses_ptr_->stamp; - // send coop request - for (auto status : cooperate_statuses_ptr_->statuses) { - if (is_path_change ^ isPathChangeModule(status.module.type)) continue; - CooperateCommand cooperate_command = setRTCCommandFromStatus(status); - cooperate_command.command.type = command; - executable_cooperate_commands_request->commands.emplace_back(cooperate_command); - // To consider needs to change path step by step - if (is_path_change && !status.auto_mode && status.command_status.type ^ command) { - break; - } - } - client_rtc_commands_->async_send_request(executable_cooperate_commands_request); -} - -void RTCManagerPanel::onClickCommandRequest(const uint8_t command) -{ - if (!cooperate_statuses_ptr_) return; - if (cooperate_statuses_ptr_->statuses.empty()) return; - auto executable_cooperate_commands_request = std::make_shared(); - executable_cooperate_commands_request->stamp = cooperate_statuses_ptr_->stamp; - // send coop request - for (auto status : cooperate_statuses_ptr_->statuses) { - CooperateCommand cooperate_command = setRTCCommandFromStatus(status); - cooperate_command.command.type = command; - executable_cooperate_commands_request->commands.emplace_back(cooperate_command); - } - client_rtc_commands_->async_send_request(executable_cooperate_commands_request); -} - -void RTCManagerPanel::onClickExecuteVelChange() -{ - onClickChangeRequest(false, Command::ACTIVATE); -} -void RTCManagerPanel::onClickWaitVelChange() -{ - onClickChangeRequest(false, Command::DEACTIVATE); -} -void RTCManagerPanel::onClickExecutePathChange() -{ - onClickChangeRequest(true, Command::ACTIVATE); -} -void RTCManagerPanel::onClickWaitPathChange() -{ - onClickChangeRequest(true, Command::DEACTIVATE); -} -void RTCManagerPanel::onClickExecution() -{ - onClickCommandRequest(Command::ACTIVATE); -} -void RTCManagerPanel::onClickWait() -{ - onClickCommandRequest(Command::DEACTIVATE); -} - -void RTCManagerPanel::onRTCStatus(const CooperateStatusArray::ConstSharedPtr msg) -{ - cooperate_statuses_ptr_ = std::make_shared(*msg); - rtc_table_->clearContents(); - num_rtc_status_ptr_->setText( - QString::fromStdString("The Number of RTC Statuses: " + std::to_string(msg->statuses.size()))); - if (msg->statuses.empty()) { - rtc_table_->update(); - return; - } - // this is to stable rtc display not to occupy too much - size_t min_display_size{5}; - size_t max_display_size{10}; - // rtc messages are already sorted by distance - rtc_table_->setRowCount( - std::max(min_display_size, std::min(msg->statuses.size(), max_display_size))); - int cnt = 0; - - auto sorted_statuses = msg->statuses; - std::partition(sorted_statuses.begin(), sorted_statuses.end(), [](const auto & status) { - return !status.auto_mode && !uint2bool(status.command_status.type); - }); - - for (auto status : sorted_statuses) { - if (static_cast(cnt) >= max_display_size) { - rtc_table_->update(); - return; - } - // uuid - { - std::stringstream uuid; - uuid << std::setw(4) << std::setfill('0') << static_cast(status.uuid.uuid.at(0)); - auto label = new QLabel(QString::fromStdString(uuid.str())); - label->setAlignment(Qt::AlignCenter); - label->setText(QString::fromStdString(uuid.str())); - rtc_table_->setCellWidget(cnt, 0, label); - } - - // module name - { - std::string module_name = getModuleName(status.module.type); - auto label = new QLabel(QString::fromStdString(module_name)); - label->setAlignment(Qt::AlignCenter); - label->setText(QString::fromStdString(module_name)); - rtc_table_->setCellWidget(cnt, 1, label); - } - - // is aw safe - bool is_aw_safe = status.safe; - { - std::string is_safe = Bool2String(is_aw_safe); - auto label = new QLabel(QString::fromStdString(is_safe)); - label->setAlignment(Qt::AlignCenter); - label->setText(QString::fromStdString(is_safe)); - rtc_table_->setCellWidget(cnt, 2, label); - } - - // is operator safe - const bool is_execute = uint2bool(status.command_status.type); - { - std::string text = is_execute ? "EXECUTE" : "WAIT"; - if (status.auto_mode) text = "NONE"; - auto label = new QLabel(QString::fromStdString(text)); - label->setAlignment(Qt::AlignCenter); - label->setText(QString::fromStdString(text)); - rtc_table_->setCellWidget(cnt, 3, label); - } - - // is auto mode - const bool is_rtc_auto_mode = status.auto_mode; - { - std::string is_auto_mode = Bool2String(is_rtc_auto_mode); - auto label = new QLabel(QString::fromStdString(is_auto_mode)); - label->setAlignment(Qt::AlignCenter); - label->setText(QString::fromStdString(is_auto_mode)); - rtc_table_->setCellWidget(cnt, 4, label); - } - - // start distance - { - std::string start_distance = std::to_string(status.start_distance); - auto label = new QLabel(QString::fromStdString(start_distance)); - label->setAlignment(Qt::AlignCenter); - label->setText(QString::fromStdString(start_distance)); - rtc_table_->setCellWidget(cnt, 5, label); - } - - // finish distance - { - std::string finish_distance = std::to_string(status.finish_distance); - auto label = new QLabel(QString::fromStdString(finish_distance)); - label->setAlignment(Qt::AlignCenter); - label->setText(QString::fromStdString(finish_distance)); - rtc_table_->setCellWidget(cnt, 6, label); - } - - // add color for recognition - if (is_rtc_auto_mode || (is_aw_safe && is_execute)) { - rtc_table_->cellWidget(cnt, 1)->setStyleSheet(BG_GREEN); - } else if (is_aw_safe || is_execute) { - rtc_table_->cellWidget(cnt, 1)->setStyleSheet(BG_YELLOW); - } else { - rtc_table_->cellWidget(cnt, 1)->setStyleSheet(BG_RED); - } - cnt++; - } - rtc_table_->update(); -} -} // namespace rviz_plugins - -#include -PLUGINLIB_EXPORT_CLASS(rviz_plugins::RTCManagerPanel, rviz_common::Panel) diff --git a/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.hpp b/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.hpp deleted file mode 100644 index 8bdaef94b6254..0000000000000 --- a/common/rtc_manager_rviz_plugin/src/rtc_manager_panel.hpp +++ /dev/null @@ -1,132 +0,0 @@ -// -// Copyright 2020 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 RTC_MANAGER_PANEL_HPP_ -#define RTC_MANAGER_PANEL_HPP_ - -#include -#include -#include -#include -#include - -#ifndef Q_MOC_RUN -// cpp -#include -#include -#include -#include -// ros -#include -#include - -#include -// autoware -#include -#include -#include -#include -#include -#include -#include -#include -#endif - -namespace rviz_plugins -{ -using tier4_rtc_msgs::msg::Command; -using tier4_rtc_msgs::msg::CooperateCommand; -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::srv::AutoMode; -using tier4_rtc_msgs::srv::CooperateCommands; -using unique_identifier_msgs::msg::UUID; - -static const QString BG_BLUE = "background-color: #3dffff;"; -static const QString BG_YELLOW = "background-color: #ffff3d;"; -static const QString BG_PURPLE = "background-color: #9e3dff;"; -static const QString BG_ORANGE = "background-color: #ff7f00;"; -static const QString BG_GREEN = "background-color: #3dff3d;"; -static const QString BG_RED = "background-color: #ff3d3d;"; - -struct RTCAutoMode : public QObject -{ - Q_OBJECT - -public Q_SLOTS: - void onChangeToAutoMode(); - void onChangeToManualMode(); - -public: - std::string module_name; - QPushButton * auto_module_button_ptr; - QPushButton * manual_module_button_ptr; - QLabel * auto_manual_mode_label; - rclcpp::Client::SharedPtr enable_auto_mode_cli; -}; - -class RTCManagerPanel : public rviz_common::Panel -{ - Q_OBJECT -public Q_SLOTS: - void onClickExecution(); - void onClickWait(); - void onClickVelocityChangeRequest(); - void onClickExecutePathChange(); - void onClickWaitPathChange(); - void onClickExecuteVelChange(); - void onClickWaitVelChange(); - -public: - explicit RTCManagerPanel(QWidget * parent = nullptr); - void onInitialize() override; - -protected: - void onRTCStatus(const CooperateStatusArray::ConstSharedPtr msg); - void onEnableService( - const AutoMode::Request::SharedPtr request, const AutoMode::Response::SharedPtr response) const; - void onClickCommandRequest(const uint8_t command); - void onClickChangeRequest(const bool is_path_change, const uint8_t command); - -private: - rclcpp::Node::SharedPtr raw_node_; - rclcpp::Subscription::SharedPtr sub_rtc_status_; - rclcpp::Client::SharedPtr client_rtc_commands_; - rclcpp::Client::SharedPtr enable_auto_mode_cli_; - std::vector auto_modes_; - - std::shared_ptr cooperate_statuses_ptr_; - QTableWidget * rtc_table_; - QTableWidget * auto_mode_table_; - QPushButton * path_change_button_ptr_ = {nullptr}; - QPushButton * velocity_change_button_ptr_ = {nullptr}; - QPushButton * exec_path_change_button_ptr_ = {nullptr}; - QPushButton * wait_path_change_button_ptr_ = {nullptr}; - QPushButton * exec_vel_change_button_ptr_ = {nullptr}; - QPushButton * wait_vel_change_button_ptr_ = {nullptr}; - QPushButton * exec_button_ptr_ = {nullptr}; - QPushButton * wait_button_ptr_ = {nullptr}; - QLabel * num_rtc_status_ptr_ = {nullptr}; - - size_t column_size_ = {7}; - std::string enable_auto_mode_namespace_ = "/planning/enable_auto_mode"; -}; - -} // namespace rviz_plugins - -#endif // RTC_MANAGER_PANEL_HPP_ diff --git a/common/tier4_automatic_goal_rviz_plugin/CMakeLists.txt b/common/tier4_automatic_goal_rviz_plugin/CMakeLists.txt deleted file mode 100644 index cdc57743a6cb1..0000000000000 --- a/common/tier4_automatic_goal_rviz_plugin/CMakeLists.txt +++ /dev/null @@ -1,36 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(tier4_automatic_goal_rviz_plugin) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -find_package(Qt5 REQUIRED Core Widgets) -set(QT_LIBRARIES Qt5::Widgets) -set(CMAKE_AUTOMOC ON) -set(CMAKE_INCLUDE_CURRENT_DIR ON) -add_definitions(-DQT_NO_KEYWORDS) - -ament_auto_add_library(${PROJECT_NAME} SHARED - src/automatic_checkpoint_append_tool.cpp - src/automatic_goal_sender.cpp - src/automatic_goal_append_tool.cpp - src/automatic_goal_panel.cpp -) - -ament_auto_add_executable(automatic_goal_sender - src/automatic_goal_sender.cpp -) - -target_link_libraries(${PROJECT_NAME} - ${QT_LIBRARIES} -) - -# 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 - launch - icons - plugins -) diff --git a/common/tier4_automatic_goal_rviz_plugin/README.md b/common/tier4_automatic_goal_rviz_plugin/README.md deleted file mode 100644 index 6fd626d5a7642..0000000000000 --- a/common/tier4_automatic_goal_rviz_plugin/README.md +++ /dev/null @@ -1,98 +0,0 @@ -# tier4_automatic_goal_rviz_plugin - -## Purpose - -1. Defining a `GoalsList` by adding goals using `RvizTool` (Pose on the map). - -2. Automatic execution of the created `GoalsList` from the selected goal - it can be stopped and restarted. - -3. Looping the current `GoalsList`. - -4. Saving achieved goals to a file. - -5. Plan the route to one (single) selected goal and starting that route - it can be stopped and restarted. - -6. Remove any goal from the list or clear the current route. - -7. Save the current `GoalsList` to a file and load the list from the file. - -8. The application enables/disables access to options depending on the current state. - -9. The saved `GoalsList` can be executed without using a plugin - using a node `automatic_goal_sender`. - -## Inputs / Outputs - -### Input - -| Name | Type | Description | -| ---------------------------- | ------------------------------------------------- | ------------------------------------------------ | -| `/api/operation_mode/state` | `autoware_adapi_v1_msgs::msg::OperationModeState` | The topic represents the state of operation mode | -| `/api/routing/state` | `autoware_adapi_v1_msgs::msg::RouteState` | The topic represents the state of route | -| `/rviz2/automatic_goal/goal` | `geometry_msgs::msgs::PoseStamped` | The topic for adding goals to GoalsList | - -### Output - -| Name | Type | Description | -| ------------------------------------------ | -------------------------------------------------- | -------------------------------------------------- | -| `/api/operation_mode/change_to_autonomous` | `autoware_adapi_v1_msgs::srv::ChangeOperationMode` | The service to change operation mode to autonomous | -| `/api/operation_mode/change_to_stop` | `autoware_adapi_v1_msgs::srv::ChangeOperationMode` | The service to change operation mode to stop | -| `/api/routing/set_route_points` | `autoware_adapi_v1_msgs::srv::SetRoutePoints` | The service to set route | -| `/api/routing/clear_route` | `autoware_adapi_v1_msgs::srv::ClearRoute` | The service to clear route state | -| `/rviz2/automatic_goal/markers` | `visualization_msgs::msg::MarkerArray` | The topic to visualize goals as rviz markers | - -## HowToUse - -1. Start rviz and select panels/Add new panel. - - ![select_panel](./images/select_panels.png) - -2. Select `tier4_automatic_goal_rviz_plugin/AutowareAutomaticGoalPanel` and press OK. - -3. Select Add a new tool. - - ![select_tool](./images/select_tool.png) - -4. Select `tier4_automatic_goal_rviz_plugin/AutowareAutomaticGoalTool` and press OK. - -5. Add goals visualization as markers to `Displays`. - - ![markers](./images/markers.png) - -6. Append goals to the `GoalsList` to be achieved using `2D Append Goal` - in such a way that routes can be planned. - -7. Start sequential planning and goal achievement by clicking `Send goals automatically` - - ![panel](./images/panel.png) - -8. You can save `GoalsList` by clicking `Save to file`. - -9. After saving, you can run the `GoalsList` without using a plugin also: - - example: `ros2 launch tier4_automatic_goal_rviz_plugin automatic_goal_sender.launch.xml goals_list_file_path:="/tmp/goals_list.yaml" goals_achieved_dir_path:="/tmp/"` - - `goals_list_file_path` - is the path to the saved `GoalsList` file to be loaded - - `goals_achieved_dir_path` - is the path to the directory where the file `goals_achieved.log` will be created and the achieved goals will be written to it - -### Hints - -If the application (Engagement) goes into `ERROR` mode (usually returns to `EDITING` later), it means that one of the services returned a calling error (`code!=0`). -In this situation, check the terminal output for more information. - -- Often it is enough to try again. -- Sometimes a clearing of the current route is required before retrying. - -## Material Design Icons - -This project uses [Material Design Icons](https://developers.google.com/fonts/docs/material_symbols) by Google. These icons are used under the terms of the Apache License, Version 2.0. - -Material Design Icons are a collection of symbols provided by Google that are used to enhance the user interface of applications, websites, and other digital products. - -### License - -The Material Design Icons are licensed under the Apache License, Version 2.0. You may obtain a copy of the License at: - - - -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. - -### Acknowledgments - -We would like to express our gratitude to Google for making these icons available to the community, helping developers and designers enhance the visual appeal and user experience of their projects. diff --git a/common/tier4_automatic_goal_rviz_plugin/icons/classes/AutowareAutomaticCheckpointTool.png b/common/tier4_automatic_goal_rviz_plugin/icons/classes/AutowareAutomaticCheckpointTool.png deleted file mode 100644 index 4f5b4961f2500..0000000000000 Binary files a/common/tier4_automatic_goal_rviz_plugin/icons/classes/AutowareAutomaticCheckpointTool.png and /dev/null differ diff --git a/common/tier4_automatic_goal_rviz_plugin/icons/classes/AutowareAutomaticGoalPanel.png b/common/tier4_automatic_goal_rviz_plugin/icons/classes/AutowareAutomaticGoalPanel.png deleted file mode 100644 index 6a67573717ae1..0000000000000 Binary files a/common/tier4_automatic_goal_rviz_plugin/icons/classes/AutowareAutomaticGoalPanel.png and /dev/null differ diff --git a/common/tier4_automatic_goal_rviz_plugin/icons/classes/AutowareAutomaticGoalTool.png b/common/tier4_automatic_goal_rviz_plugin/icons/classes/AutowareAutomaticGoalTool.png deleted file mode 100644 index 58d12f95ebfd6..0000000000000 Binary files a/common/tier4_automatic_goal_rviz_plugin/icons/classes/AutowareAutomaticGoalTool.png and /dev/null differ diff --git a/common/tier4_automatic_goal_rviz_plugin/images/markers.png b/common/tier4_automatic_goal_rviz_plugin/images/markers.png deleted file mode 100644 index 8dd4d9d02bef4..0000000000000 Binary files a/common/tier4_automatic_goal_rviz_plugin/images/markers.png and /dev/null differ diff --git a/common/tier4_automatic_goal_rviz_plugin/images/panel.png b/common/tier4_automatic_goal_rviz_plugin/images/panel.png deleted file mode 100644 index 1800202ea9f57..0000000000000 Binary files a/common/tier4_automatic_goal_rviz_plugin/images/panel.png and /dev/null differ diff --git a/common/tier4_automatic_goal_rviz_plugin/images/select_panels.png b/common/tier4_automatic_goal_rviz_plugin/images/select_panels.png deleted file mode 100644 index 61dd9e1d7a1b3..0000000000000 Binary files a/common/tier4_automatic_goal_rviz_plugin/images/select_panels.png and /dev/null differ diff --git a/common/tier4_automatic_goal_rviz_plugin/images/select_tool.png b/common/tier4_automatic_goal_rviz_plugin/images/select_tool.png deleted file mode 100644 index a6ddc6d24c575..0000000000000 Binary files a/common/tier4_automatic_goal_rviz_plugin/images/select_tool.png and /dev/null differ diff --git a/common/tier4_automatic_goal_rviz_plugin/launch/automatic_goal_sender.launch.xml b/common/tier4_automatic_goal_rviz_plugin/launch/automatic_goal_sender.launch.xml deleted file mode 100644 index a9af89c078348..0000000000000 --- a/common/tier4_automatic_goal_rviz_plugin/launch/automatic_goal_sender.launch.xml +++ /dev/null @@ -1,10 +0,0 @@ - - - - - - - - - - diff --git a/common/tier4_automatic_goal_rviz_plugin/package.xml b/common/tier4_automatic_goal_rviz_plugin/package.xml deleted file mode 100644 index fb5331379acb6..0000000000000 --- a/common/tier4_automatic_goal_rviz_plugin/package.xml +++ /dev/null @@ -1,38 +0,0 @@ - - - - tier4_automatic_goal_rviz_plugin - 0.0.0 - The autoware automatic goal rviz plugin package - Shumpei Wakabayashi - Dawid Moszyński - Kyoichi Sugahara - Satoshi Ota - Apache License 2.0 - Dawid Moszyński - - ament_cmake_auto - autoware_cmake - autoware_adapi_v1_msgs - geometry_msgs - libqt5-core - libqt5-gui - libqt5-widgets - qtbase5-dev - rclcpp - rviz_common - rviz_default_plugins - tf2 - tf2_geometry_msgs - tier4_autoware_utils - visualization_msgs - yaml-cpp - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - - diff --git a/common/tier4_automatic_goal_rviz_plugin/plugins/plugin_description.xml b/common/tier4_automatic_goal_rviz_plugin/plugins/plugin_description.xml deleted file mode 100644 index e9d77491941ed..0000000000000 --- a/common/tier4_automatic_goal_rviz_plugin/plugins/plugin_description.xml +++ /dev/null @@ -1,17 +0,0 @@ - - - AutowareAutomaticGoalPanel - - - AutowareAutomaticGoalTool - - - AutowareAutomaticCheckpointTool - - diff --git a/common/tier4_automatic_goal_rviz_plugin/src/automatic_checkpoint_append_tool.cpp b/common/tier4_automatic_goal_rviz_plugin/src/automatic_checkpoint_append_tool.cpp deleted file mode 100644 index 4efa6fedbaabd..0000000000000 --- a/common/tier4_automatic_goal_rviz_plugin/src/automatic_checkpoint_append_tool.cpp +++ /dev/null @@ -1,122 +0,0 @@ -// 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) 2012, 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 Willow Garage, Inc. 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 "automatic_checkpoint_append_tool.hpp" - -#ifdef ROS_DISTRO_GALACTIC -#include -#else -#include -#endif -#include - -#include - -namespace rviz_plugins -{ -AutowareAutomaticCheckpointTool::AutowareAutomaticCheckpointTool() -{ - shortcut_key_ = 'c'; - - pose_topic_property_ = new rviz_common::properties::StringProperty( - "Pose Topic", "~/automatic_goal/checkpoint", "The topic on which to publish automatic_goal.", - getPropertyContainer(), SLOT(updateTopic()), this); - std_dev_x_ = new rviz_common::properties::FloatProperty( - "X std deviation", 0.5, "X standard deviation for checkpoint pose [m]", getPropertyContainer()); - std_dev_y_ = new rviz_common::properties::FloatProperty( - "Y std deviation", 0.5, "Y standard deviation for checkpoint pose [m]", getPropertyContainer()); - std_dev_theta_ = new rviz_common::properties::FloatProperty( - "Theta std deviation", M_PI / 12.0, "Theta standard deviation for checkpoint pose [rad]", - getPropertyContainer()); - position_z_ = new rviz_common::properties::FloatProperty( - "Z position", 0.0, "Z position for checkpoint pose [m]", getPropertyContainer()); - std_dev_x_->setMin(0); - std_dev_y_->setMin(0); - std_dev_theta_->setMin(0); - position_z_->setMin(0); -} - -void AutowareAutomaticCheckpointTool::onInitialize() -{ - PoseTool::onInitialize(); - setName("2D AppendCheckpoint"); - updateTopic(); -} - -void AutowareAutomaticCheckpointTool::updateTopic() -{ - rclcpp::Node::SharedPtr raw_node = context_->getRosNodeAbstraction().lock()->get_raw_node(); - pose_pub_ = raw_node->create_publisher( - pose_topic_property_->getStdString(), 1); - clock_ = raw_node->get_clock(); -} - -void AutowareAutomaticCheckpointTool::onPoseSet(double x, double y, double theta) -{ - // pose - std::string fixed_frame = context_->getFixedFrame().toStdString(); - geometry_msgs::msg::PoseStamped pose; - pose.header.frame_id = fixed_frame; - pose.header.stamp = clock_->now(); - pose.pose.position.x = x; - pose.pose.position.y = y; - pose.pose.position.z = position_z_->getFloat(); - - tf2::Quaternion quat; - quat.setRPY(0.0, 0.0, theta); - pose.pose.orientation = tf2::toMsg(quat); - RCLCPP_INFO( - rclcpp::get_logger("AutowareAutomaticCheckpointTool"), - "Setting pose: %.3f %.3f %.3f %.3f [frame=%s]", x, y, position_z_->getFloat(), theta, - fixed_frame.c_str()); - pose_pub_->publish(pose); -} - -} // end namespace rviz_plugins - -#include -PLUGINLIB_EXPORT_CLASS(rviz_plugins::AutowareAutomaticCheckpointTool, rviz_common::Tool) diff --git a/common/tier4_automatic_goal_rviz_plugin/src/automatic_checkpoint_append_tool.hpp b/common/tier4_automatic_goal_rviz_plugin/src/automatic_checkpoint_append_tool.hpp deleted file mode 100644 index 4ea3fa4bd009a..0000000000000 --- a/common/tier4_automatic_goal_rviz_plugin/src/automatic_checkpoint_append_tool.hpp +++ /dev/null @@ -1,91 +0,0 @@ -// 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) 2012, 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 Willow Garage, Inc. 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 AUTOMATIC_CHECKPOINT_APPEND_TOOL_HPP_ -#define AUTOMATIC_CHECKPOINT_APPEND_TOOL_HPP_ - -#ifndef Q_MOC_RUN // See: https://bugreports.qt-project.org/browse/QTBUG-22829 -#include -#include -#include -#include -#include -#include -#endif - -#include - -namespace rviz_plugins -{ -class AutowareAutomaticCheckpointTool : public rviz_default_plugins::tools::PoseTool -{ - Q_OBJECT - -public: - AutowareAutomaticCheckpointTool(); - void onInitialize() override; - -protected: - void onPoseSet(double x, double y, double theta) override; - -private Q_SLOTS: - void updateTopic(); - -private: // NOLINT for Qt - rclcpp::Clock::SharedPtr clock_{nullptr}; - rclcpp::Publisher::SharedPtr pose_pub_{nullptr}; - - rviz_common::properties::StringProperty * pose_topic_property_{nullptr}; - rviz_common::properties::FloatProperty * std_dev_x_{nullptr}; - rviz_common::properties::FloatProperty * std_dev_y_{nullptr}; - rviz_common::properties::FloatProperty * std_dev_theta_{nullptr}; - rviz_common::properties::FloatProperty * position_z_{nullptr}; -}; - -} // namespace rviz_plugins - -#endif // AUTOMATIC_CHECKPOINT_APPEND_TOOL_HPP_ diff --git a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_append_tool.cpp b/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_append_tool.cpp deleted file mode 100644 index 43fc0edcccf84..0000000000000 --- a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_append_tool.cpp +++ /dev/null @@ -1,121 +0,0 @@ -// 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. -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2012, 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 Willow Garage, Inc. 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 "automatic_goal_append_tool.hpp" - -#ifdef ROS_DISTRO_GALACTIC -#include -#else -#include -#endif -#include - -#include - -namespace rviz_plugins -{ -AutowareAutomaticGoalTool::AutowareAutomaticGoalTool() -{ - shortcut_key_ = 'c'; - - pose_topic_property_ = new rviz_common::properties::StringProperty( - "Pose Topic", "~/automatic_goal/goal", "The topic on which to publish automatic_goal.", - getPropertyContainer(), SLOT(updateTopic()), this); - std_dev_x_ = new rviz_common::properties::FloatProperty( - "X std deviation", 0.5, "X standard deviation for checkpoint pose [m]", getPropertyContainer()); - std_dev_y_ = new rviz_common::properties::FloatProperty( - "Y std deviation", 0.5, "Y standard deviation for checkpoint pose [m]", getPropertyContainer()); - std_dev_theta_ = new rviz_common::properties::FloatProperty( - "Theta std deviation", M_PI / 12.0, "Theta standard deviation for checkpoint pose [rad]", - getPropertyContainer()); - position_z_ = new rviz_common::properties::FloatProperty( - "Z position", 0.0, "Z position for checkpoint pose [m]", getPropertyContainer()); - std_dev_x_->setMin(0); - std_dev_y_->setMin(0); - std_dev_theta_->setMin(0); - position_z_->setMin(0); -} - -void AutowareAutomaticGoalTool::onInitialize() -{ - PoseTool::onInitialize(); - setName("2D AppendGoal"); - updateTopic(); -} - -void AutowareAutomaticGoalTool::updateTopic() -{ - rclcpp::Node::SharedPtr raw_node = context_->getRosNodeAbstraction().lock()->get_raw_node(); - pose_pub_ = raw_node->create_publisher( - pose_topic_property_->getStdString(), 1); - clock_ = raw_node->get_clock(); -} - -void AutowareAutomaticGoalTool::onPoseSet(double x, double y, double theta) -{ - // pose - std::string fixed_frame = context_->getFixedFrame().toStdString(); - geometry_msgs::msg::PoseStamped pose; - pose.header.frame_id = fixed_frame; - pose.header.stamp = clock_->now(); - pose.pose.position.x = x; - pose.pose.position.y = y; - pose.pose.position.z = position_z_->getFloat(); - - tf2::Quaternion quat; - quat.setRPY(0.0, 0.0, theta); - pose.pose.orientation = tf2::toMsg(quat); - RCLCPP_INFO( - rclcpp::get_logger("AutowareAutomaticGoalTool"), "Setting pose: %.3f %.3f %.3f %.3f [frame=%s]", - x, y, position_z_->getFloat(), theta, fixed_frame.c_str()); - pose_pub_->publish(pose); -} - -} // end namespace rviz_plugins - -#include -PLUGINLIB_EXPORT_CLASS(rviz_plugins::AutowareAutomaticGoalTool, rviz_common::Tool) diff --git a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_append_tool.hpp b/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_append_tool.hpp deleted file mode 100644 index 6fc98cee9afa1..0000000000000 --- a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_append_tool.hpp +++ /dev/null @@ -1,91 +0,0 @@ -// 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. -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2012, 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 Willow Garage, Inc. 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 AUTOMATIC_GOAL_APPEND_TOOL_HPP_ -#define AUTOMATIC_GOAL_APPEND_TOOL_HPP_ - -#ifndef Q_MOC_RUN // See: https://bugreports.qt-project.org/browse/QTBUG-22829 -#include -#include -#include -#include -#include -#include -#endif - -#include - -namespace rviz_plugins -{ -class AutowareAutomaticGoalTool : public rviz_default_plugins::tools::PoseTool -{ - Q_OBJECT - -public: - AutowareAutomaticGoalTool(); - void onInitialize() override; - -protected: - void onPoseSet(double x, double y, double theta) override; - -private Q_SLOTS: - void updateTopic(); - -private: // NOLINT for Qt - rclcpp::Clock::SharedPtr clock_{nullptr}; - rclcpp::Publisher::SharedPtr pose_pub_{nullptr}; - - rviz_common::properties::StringProperty * pose_topic_property_{nullptr}; - rviz_common::properties::FloatProperty * std_dev_x_{nullptr}; - rviz_common::properties::FloatProperty * std_dev_y_{nullptr}; - rviz_common::properties::FloatProperty * std_dev_theta_{nullptr}; - rviz_common::properties::FloatProperty * position_z_{nullptr}; -}; - -} // namespace rviz_plugins - -#endif // AUTOMATIC_GOAL_APPEND_TOOL_HPP_ diff --git a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_panel.cpp b/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_panel.cpp deleted file mode 100644 index 6b8d7765a989a..0000000000000 --- a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_panel.cpp +++ /dev/null @@ -1,532 +0,0 @@ -// -// Copyright 2023 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 "automatic_goal_panel.hpp" - -#include - -namespace rviz_plugins -{ -AutowareAutomaticGoalPanel::AutowareAutomaticGoalPanel(QWidget * parent) -: rviz_common::Panel(parent) -{ - qt_timer_ = new QTimer(this); - connect( - qt_timer_, &QTimer::timeout, this, &AutowareAutomaticGoalPanel::updateAutoExecutionTimerTick); - - auto * h_layout = new QHBoxLayout(this); - auto * v_layout = new QVBoxLayout(this); - h_layout->addWidget(makeGoalsListGroup()); - v_layout->addWidget(makeEngagementGroup()); - v_layout->addWidget(makeRoutingGroup()); - h_layout->addLayout(v_layout); - setLayout(h_layout); -} - -// Layouts -QGroupBox * AutowareAutomaticGoalPanel::makeGoalsListGroup() -{ - auto * group = new QGroupBox("GoalsList", this); - auto * grid = new QGridLayout(group); - - load_file_btn_ptr_ = new QPushButton("Load from file", group); - connect(load_file_btn_ptr_, SIGNAL(clicked()), SLOT(onClickLoadListFromFile())); - grid->addWidget(load_file_btn_ptr_, 0, 0); - - save_file_btn_ptr_ = new QPushButton("Save to file", group); - connect(save_file_btn_ptr_, SIGNAL(clicked()), SLOT(onClickSaveListToFile())); - grid->addWidget(save_file_btn_ptr_, 1, 0); - - goals_list_widget_ptr_ = new QListWidget(group); - goals_list_widget_ptr_->setStyleSheet("border:1px solid black;"); - grid->addWidget(goals_list_widget_ptr_, 2, 0); - - remove_selected_goal_btn_ptr_ = new QPushButton("Remove selected", group); - connect(remove_selected_goal_btn_ptr_, SIGNAL(clicked()), SLOT(onClickRemove())); - grid->addWidget(remove_selected_goal_btn_ptr_, 3, 0); - - loop_list_btn_ptr_ = new QPushButton("Loop list", group); - loop_list_btn_ptr_->setCheckable(true); - connect(loop_list_btn_ptr_, SIGNAL(toggled(bool)), SLOT(onToggleLoopList(bool))); - grid->addWidget(loop_list_btn_ptr_, 4, 0); - - goals_achieved_btn_ptr_ = new QPushButton("Saving achieved goals to file", group); - goals_achieved_btn_ptr_->setCheckable(true); - connect(goals_achieved_btn_ptr_, SIGNAL(toggled(bool)), SLOT(onToggleSaveGoalsAchievement(bool))); - grid->addWidget(goals_achieved_btn_ptr_, 5, 0); - - group->setLayout(grid); - return group; -} - -QGroupBox * AutowareAutomaticGoalPanel::makeRoutingGroup() -{ - auto * group = new QGroupBox("Routing", this); - auto * grid = new QGridLayout(group); - - routing_label_ptr_ = new QLabel("INIT", group); - routing_label_ptr_->setMinimumSize(100, 25); - routing_label_ptr_->setAlignment(Qt::AlignCenter); - routing_label_ptr_->setStyleSheet("border:1px solid black;"); - grid->addWidget(routing_label_ptr_, 0, 0); - - clear_route_btn_ptr_ = new QPushButton("Clear planned route", group); - connect(clear_route_btn_ptr_, &QPushButton::clicked, [this]() { onClickClearRoute(); }); - grid->addWidget(clear_route_btn_ptr_, 1, 0); - group->setLayout(grid); - - group->setLayout(grid); - return group; -} - -QGroupBox * AutowareAutomaticGoalPanel::makeEngagementGroup() -{ - auto * group = new QGroupBox("Engagement", this); - auto * grid = new QGridLayout(group); - - engagement_label_ptr_ = new QLabel("INITIALIZING", group); - engagement_label_ptr_->setMinimumSize(100, 25); - engagement_label_ptr_->setAlignment(Qt::AlignCenter); - engagement_label_ptr_->setStyleSheet("border:1px solid black;"); - grid->addWidget(engagement_label_ptr_, 0, 0); - - automatic_mode_btn_ptr_ = new QPushButton("Send goals automatically", group); - automatic_mode_btn_ptr_->setCheckable(true); - - connect(automatic_mode_btn_ptr_, SIGNAL(toggled(bool)), SLOT(onToggleAutoMode(bool))); - grid->addWidget(automatic_mode_btn_ptr_, 1, 0); - - plan_btn_ptr_ = new QPushButton("Plan to selected goal", group); - connect(plan_btn_ptr_, &QPushButton::clicked, [this] { onClickPlan(); }); - grid->addWidget(plan_btn_ptr_, 2, 0); - - start_btn_ptr_ = new QPushButton("Start current plan", group); - connect(start_btn_ptr_, &QPushButton::clicked, [this] { onClickStart(); }); - grid->addWidget(start_btn_ptr_, 3, 0); - - stop_btn_ptr_ = new QPushButton("Stop current plan", group); - connect(stop_btn_ptr_, SIGNAL(clicked()), SLOT(onClickStop())); - grid->addWidget(stop_btn_ptr_, 4, 0); - group->setLayout(grid); - - group->setLayout(grid); - return group; -} - -void AutowareAutomaticGoalPanel::showMessageBox(const QString & string) -{ - QMessageBox msg_box(this); - msg_box.setText(string); - msg_box.exec(); -} - -// Slots -void AutowareAutomaticGoalPanel::onInitialize() -{ - raw_node_ = this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); - pub_marker_ = raw_node_->create_publisher("~/automatic_goal/markers", 0); - sub_append_goal_ = raw_node_->create_subscription( - "~/automatic_goal/goal", 5, - std::bind(&AutowareAutomaticGoalPanel::onAppendGoal, this, std::placeholders::_1)); - sub_append_checkpoint_ = raw_node_->create_subscription( - "~/automatic_goal/checkpoint", 5, - std::bind(&AutowareAutomaticGoalPanel::onAppendCheckpoint, this, std::placeholders::_1)); - initCommunication(raw_node_.get()); -} - -void AutowareAutomaticGoalPanel::onToggleLoopList(bool checked) -{ - is_loop_list_on_ = checked; - updateGUI(); -} - -void AutowareAutomaticGoalPanel::onToggleSaveGoalsAchievement(bool checked) -{ - if (checked) { - QString file_name = QFileDialog::getSaveFileName( - this, tr("Save File with GoalsList"), "/tmp/goals_achieved.log", - tr("Achieved goals (*.log)")); - goals_achieved_file_path_ = file_name.toStdString(); - } else { - goals_achieved_file_path_ = ""; - } - updateGUI(); -} - -void AutowareAutomaticGoalPanel::onToggleAutoMode(bool checked) -{ - if (checked && goals_list_widget_ptr_->selectedItems().count() != 1) { - showMessageBox("Select the first goal in GoalsList"); - automatic_mode_btn_ptr_->setChecked(false); - } else { - if (checked) current_goal_ = goals_list_widget_ptr_->currentRow(); - is_automatic_mode_on_ = checked; - is_automatic_mode_on_ ? qt_timer_->start(1000) : qt_timer_->stop(); - onClickClearRoute(); // here will be set State::AUTO_NEXT or State::EDITING; - } -} - -void AutowareAutomaticGoalPanel::onClickPlan() -{ - if (goals_list_widget_ptr_->selectedItems().count() != 1) { - showMessageBox("Select a goal in GoalsList"); - return; - } - - if (callPlanToGoalIndex(cli_set_route_, goals_list_widget_ptr_->currentRow())) { - state_ = State::PLANNING; - updateGUI(); - } -} - -void AutowareAutomaticGoalPanel::onClickStart() -{ - if (callService(cli_change_to_autonomous_)) { - state_ = State::STARTING; - updateGUI(); - } -} - -void AutowareAutomaticGoalPanel::onClickStop() -{ - // if ERROR is set then the ego is already stopped - if (state_ == State::ERROR) { - state_ = State::STOPPED; - updateGUI(); - } else if (callService(cli_change_to_stop_)) { - state_ = State::STOPPING; - updateGUI(); - } -} - -void AutowareAutomaticGoalPanel::onClickClearRoute() -{ - if (callService(cli_clear_route_)) { - state_ = State::CLEARING; - updateGUI(); - } -} - -void AutowareAutomaticGoalPanel::onClickRemove() -{ - if (static_cast(goals_list_widget_ptr_->currentRow()) < goals_list_.size()) - goals_list_.erase(goals_list_.begin() + goals_list_widget_ptr_->currentRow()); - resetAchievedGoals(); - updateGUI(); - updateGoalsList(); -} - -void AutowareAutomaticGoalPanel::onClickLoadListFromFile() -{ - QString file_name = QFileDialog::getOpenFileName( - this, tr("Open File with GoalsList"), "/tmp", tr("Goal lists (*.yaml)")); - if (file_name.count() > 0) loadGoalsList(file_name.toStdString()); -} - -void AutowareAutomaticGoalPanel::onClickSaveListToFile() -{ - if (!goals_list_.empty()) { - QString file_name = QFileDialog::getSaveFileName( - this, tr("Save File with GoalsList"), "/tmp/goals_list.yaml", tr("Goal lists (*.yaml)")); - if (file_name.count() > 0) saveGoalsList(file_name.toStdString()); - } -} - -// Inputs -void AutowareAutomaticGoalPanel::onAppendGoal(const PoseStamped::ConstSharedPtr pose) -{ - if (state_ == State::EDITING) { - goals_list_.emplace_back(pose); - updateGoalsList(); - updateGUI(); - } -} - -void AutowareAutomaticGoalPanel::onAppendCheckpoint(const PoseStamped::ConstSharedPtr pose) -{ - if (goals_list_widget_ptr_->selectedItems().count() != 1) { - showMessageBox("Select a goal in GoalsList before set checkpoint"); - return; - } - - current_goal_ = goals_list_widget_ptr_->currentRow(); - if (current_goal_ >= goals_list_.size()) { - return; - } - - goals_list_.at(current_goal_).checkpoint_pose_ptrs.push_back(pose); - publishMarkers(); -} - -// Override -void AutowareAutomaticGoalPanel::onCallResult() -{ - updateGUI(); -} -void AutowareAutomaticGoalPanel::onGoalListUpdated() -{ - goals_list_widget_ptr_->clear(); - for (auto const & goal : goals_achieved_) { - auto * item = - new QListWidgetItem(QString::fromStdString(goal.second.first), goals_list_widget_ptr_); - goals_list_widget_ptr_->addItem(item); - updateGoalIcon(goals_list_widget_ptr_->count() - 1, QColor("lightGray")); - } - publishMarkers(); -} -void AutowareAutomaticGoalPanel::onOperationModeUpdated(const OperationModeState::ConstSharedPtr) -{ - updateGUI(); -} -void AutowareAutomaticGoalPanel::onRouteUpdated(const RouteState::ConstSharedPtr msg) -{ - std::pair style; - if (msg->state == RouteState::UNSET) - style = std::make_pair("UNSET", "background-color: #FFFF00;"); // yellow - else if (msg->state == RouteState::SET) - style = std::make_pair("SET", "background-color: #00FF00;"); // green - else if (msg->state == RouteState::ARRIVED) - style = std::make_pair("ARRIVED", "background-color: #FFA500;"); // orange - else if (msg->state == RouteState::CHANGING) - style = std::make_pair("CHANGING", "background-color: #FFFF00;"); // yellow - else - style = std::make_pair("UNKNOWN", "background-color: #FF0000;"); // red - - updateLabel(routing_label_ptr_, style.first, style.second); - updateGUI(); -} - -void AutowareAutomaticGoalPanel::updateAutoExecutionTimerTick() -{ - if (is_automatic_mode_on_) { - if (state_ == State::AUTO_NEXT) { - // end if loop is off - if (current_goal_ >= goals_list_.size() && !is_loop_list_on_) { - disableAutomaticMode(); - return; - } - // plan to next goal - current_goal_ = current_goal_ % goals_list_.size(); - if (callPlanToGoalIndex(cli_set_route_, current_goal_)) { - state_ = State::PLANNING; - updateGUI(); - } - } else if (state_ == State::PLANNED) { - updateGoalIcon(current_goal_, QColor("yellow")); - onClickStart(); - } else if (state_ == State::ARRIVED) { - goals_achieved_[current_goal_].second++; - updateAchievedGoalsFile(current_goal_); - updateGoalIcon(current_goal_++, QColor("green")); - onClickClearRoute(); // will be set AUTO_NEXT as next state_ - } else if (state_ == State::STOPPED || state_ == State::ERROR) { - disableAutomaticMode(); - } - } -} - -// Visual updates -void AutowareAutomaticGoalPanel::updateGUI() -{ - deactivateButton(automatic_mode_btn_ptr_); - deactivateButton(remove_selected_goal_btn_ptr_); - deactivateButton(clear_route_btn_ptr_); - deactivateButton(plan_btn_ptr_); - deactivateButton(start_btn_ptr_); - deactivateButton(stop_btn_ptr_); - deactivateButton(load_file_btn_ptr_); - deactivateButton(save_file_btn_ptr_); - deactivateButton(loop_list_btn_ptr_); - deactivateButton(goals_achieved_btn_ptr_); - - std::pair style; - switch (state_) { - case State::EDITING: - activateButton(load_file_btn_ptr_); - if (!goals_list_.empty()) { - activateButton(goals_achieved_btn_ptr_); - activateButton(plan_btn_ptr_); - activateButton(remove_selected_goal_btn_ptr_); - activateButton(automatic_mode_btn_ptr_); - activateButton(save_file_btn_ptr_); - activateButton(loop_list_btn_ptr_); - } - style = std::make_pair("EDITING", "background-color: #FFFF00;"); - break; - case State::PLANNED: - activateButton(start_btn_ptr_); - activateButton(clear_route_btn_ptr_); - activateButton(save_file_btn_ptr_); - style = std::make_pair("PLANNED", "background-color: #00FF00;"); - break; - case State::STARTED: - activateButton(stop_btn_ptr_); - activateButton(save_file_btn_ptr_); - style = std::make_pair("STARTED", "background-color: #00FF00;"); - break; - case State::STOPPED: - activateButton(start_btn_ptr_); - activateButton(automatic_mode_btn_ptr_); - activateButton(clear_route_btn_ptr_); - activateButton(save_file_btn_ptr_); - style = std::make_pair("STOPPED", "background-color: #00FF00;"); - break; - case State::ARRIVED: - if (!is_automatic_mode_on_) onClickClearRoute(); // will be set EDITING as next state_ - break; - case State::CLEARED: - is_automatic_mode_on_ ? state_ = State::AUTO_NEXT : state_ = State::EDITING; - updateGUI(); - break; - case State::ERROR: - activateButton(stop_btn_ptr_); - if (!goals_list_.empty()) activateButton(save_file_btn_ptr_); - style = std::make_pair("ERROR", "background-color: #FF0000;"); - break; - case State::PLANNING: - activateButton(clear_route_btn_ptr_); - style = std::make_pair("PLANNING", "background-color: #FFA500;"); - break; - case State::STARTING: - style = std::make_pair("STARTING", "background-color: #FFA500;"); - break; - case State::STOPPING: - style = std::make_pair("STOPPING", "background-color: #FFA500;"); - break; - case State::CLEARING: - style = std::make_pair("CLEARING", "background-color: #FFA500;"); - break; - default: - break; - } - - automatic_mode_btn_ptr_->setStyleSheet(""); - loop_list_btn_ptr_->setStyleSheet(""); - goals_achieved_btn_ptr_->setStyleSheet(""); - if (is_automatic_mode_on_) automatic_mode_btn_ptr_->setStyleSheet("background-color: green"); - if (is_loop_list_on_) loop_list_btn_ptr_->setStyleSheet("background-color: green"); - if (!goals_achieved_file_path_.empty()) - goals_achieved_btn_ptr_->setStyleSheet("background-color: green"); - - updateLabel(engagement_label_ptr_, style.first, style.second); -} - -void AutowareAutomaticGoalPanel::updateGoalIcon(const unsigned goal_index, const QColor & color) -{ - QPixmap pixmap(24, 24); - pixmap.fill(color); - QPainter painter(&pixmap); - painter.setPen(QColor("black")); - painter.setFont(QFont("fixed-width", 10)); - QString text = QString::number(goals_achieved_[goal_index].second); - painter.drawText(QRect(0, 0, 24, 24), Qt::AlignCenter, text); - QIcon icon(pixmap); - goals_list_widget_ptr_->item(static_cast(goal_index))->setIcon(icon); -} - -void AutowareAutomaticGoalPanel::publishMarkers() -{ - using tier4_autoware_utils::createDefaultMarker; - using tier4_autoware_utils::createMarkerColor; - using tier4_autoware_utils::createMarkerScale; - - MarkerArray text_array; - MarkerArray arrow_array; - // Clear existing - { - auto marker = createDefaultMarker( - "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "names", 0L, Marker::CUBE, - createMarkerScale(1.0, 1.0, 1.0), createMarkerColor(1.0, 1.0, 1.0, 0.999)); - marker.action = visualization_msgs::msg::Marker::DELETEALL; - text_array.markers.push_back(marker); - pub_marker_->publish(text_array); - } - - { - auto marker = createDefaultMarker( - "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "poses", 0L, Marker::CUBE, - createMarkerScale(1.0, 1.0, 1.0), createMarkerColor(1.0, 1.0, 1.0, 0.999)); - arrow_array.markers.push_back(marker); - pub_marker_->publish(arrow_array); - } - - text_array.markers.clear(); - arrow_array.markers.clear(); - - const auto push_arrow_marker = [&](const auto & pose, const auto & color, const size_t id) { - auto marker = createDefaultMarker( - "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "poses", id, Marker::ARROW, - createMarkerScale(1.6, 0.5, 0.5), color); - marker.action = visualization_msgs::msg::Marker::ADD; - marker.pose = pose; - marker.lifetime = rclcpp::Duration(0, 0); - marker.frame_locked = false; - arrow_array.markers.push_back(marker); - }; - - const auto push_text_marker = [&](const auto & pose, const auto & text, const size_t id) { - auto marker = createDefaultMarker( - "map", rclcpp::Clock{RCL_ROS_TIME}.now(), "names", id, Marker::TEXT_VIEW_FACING, - createMarkerScale(1.6, 1.6, 1.6), createMarkerColor(1.0, 1.0, 1.0, 0.999)); - marker.action = visualization_msgs::msg::Marker::ADD; - marker.pose = pose; - marker.lifetime = rclcpp::Duration(0, 0); - marker.frame_locked = false; - marker.text = text; - text_array.markers.push_back(marker); - }; - - // Publish current - size_t id = 0; - for (size_t i = 0; i < goals_list_.size(); ++i) { - { - const auto pose = goals_list_.at(i).goal_pose_ptr->pose; - push_arrow_marker(pose, createMarkerColor(0.0, 1.0, 0.0, 0.999), id++); - push_text_marker(pose, "Goal:" + std::to_string(i), id++); - } - - for (size_t j = 0; j < goals_list_.at(i).checkpoint_pose_ptrs.size(); ++j) { - const auto pose = goals_list_.at(i).checkpoint_pose_ptrs.at(j)->pose; - push_arrow_marker(pose, createMarkerColor(1.0, 1.0, 0.0, 0.999), id++); - push_text_marker( - pose, "Checkpoint:" + std::to_string(i) + "[Goal:" + std::to_string(j) + "]", id++); - } - } - pub_marker_->publish(text_array); - pub_marker_->publish(arrow_array); -} - -// File -void AutowareAutomaticGoalPanel::saveGoalsList(const std::string & file_path) -{ - YAML::Node node; - for (unsigned i = 0; i < goals_list_.size(); ++i) { - node[i]["position_x"] = goals_list_[i].goal_pose_ptr->pose.position.x; - node[i]["position_y"] = goals_list_[i].goal_pose_ptr->pose.position.y; - node[i]["position_z"] = goals_list_[i].goal_pose_ptr->pose.position.z; - node[i]["orientation_x"] = goals_list_[i].goal_pose_ptr->pose.orientation.x; - node[i]["orientation_y"] = goals_list_[i].goal_pose_ptr->pose.orientation.y; - node[i]["orientation_z"] = goals_list_[i].goal_pose_ptr->pose.orientation.z; - node[i]["orientation_w"] = goals_list_[i].goal_pose_ptr->pose.orientation.w; - } - std::ofstream file_out(file_path); - file_out << node; - file_out.close(); -} - -} // namespace rviz_plugins -#include -PLUGINLIB_EXPORT_CLASS(rviz_plugins::AutowareAutomaticGoalPanel, rviz_common::Panel) diff --git a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_panel.hpp b/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_panel.hpp deleted file mode 100644 index 72a5bd4fb80fe..0000000000000 --- a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_panel.hpp +++ /dev/null @@ -1,151 +0,0 @@ -// -// Copyright 2023 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 AUTOMATIC_GOAL_PANEL_HPP_ -#define AUTOMATIC_GOAL_PANEL_HPP_ - -#include "automatic_goal_sender.hpp" - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include - -#include -#include -#include -#include - -namespace rviz_plugins -{ -class AutowareAutomaticGoalPanel : public rviz_common::Panel, - public automatic_goal::AutowareAutomaticGoalSender -{ - using State = automatic_goal::AutomaticGoalState; - using Pose = geometry_msgs::msg::Pose; - using PoseStamped = geometry_msgs::msg::PoseStamped; - using Marker = visualization_msgs::msg::Marker; - using MarkerArray = visualization_msgs::msg::MarkerArray; - using OperationModeState = autoware_adapi_v1_msgs::msg::OperationModeState; - using ChangeOperationMode = autoware_adapi_v1_msgs::srv::ChangeOperationMode; - using RouteState = autoware_adapi_v1_msgs::msg::RouteState; - using SetRoutePoints = autoware_adapi_v1_msgs::srv::SetRoutePoints; - using ClearRoute = autoware_adapi_v1_msgs::srv::ClearRoute; - Q_OBJECT - -public: - explicit AutowareAutomaticGoalPanel(QWidget * parent = nullptr); - void onInitialize() override; - -public Q_SLOTS: // NOLINT for Qt - void onToggleLoopList(bool checked); - void onToggleAutoMode(bool checked); - void onToggleSaveGoalsAchievement(bool checked); - void onClickPlan(); - void onClickStart(); - void onClickStop(); - void onClickClearRoute(); - void onClickRemove(); - void onClickLoadListFromFile(); - void onClickSaveListToFile(); - -private: - // Override - void updateAutoExecutionTimerTick() override; - void onRouteUpdated(const RouteState::ConstSharedPtr msg) override; - void onOperationModeUpdated(const OperationModeState::ConstSharedPtr msg) override; - void onCallResult() override; - void onGoalListUpdated() override; - - // Inputs - void onAppendGoal(const PoseStamped::ConstSharedPtr pose); - void onAppendCheckpoint(const PoseStamped::ConstSharedPtr pose); - - // Visual updates - void updateGUI(); - void updateGoalIcon(const unsigned goal_index, const QColor & color); - void publishMarkers(); - void showMessageBox(const QString & string); - void disableAutomaticMode() { automatic_mode_btn_ptr_->setChecked(false); } - static void activateButton(QAbstractButton * btn) { btn->setEnabled(true); } - static void deactivateButton(QAbstractButton * btn) { btn->setEnabled(false); } - static void updateLabel(QLabel * label, const QString & text, const QString & style_sheet) - { - label->setText(text); - label->setStyleSheet(style_sheet); - } - // File - void saveGoalsList(const std::string & file); - - // Pub/Sub - rclcpp::Publisher::SharedPtr pub_marker_{nullptr}; - rclcpp::Subscription::SharedPtr sub_append_goal_{nullptr}; - rclcpp::Subscription::SharedPtr sub_append_checkpoint_{nullptr}; - - // Containers - rclcpp::Node::SharedPtr raw_node_{nullptr}; - bool is_automatic_mode_on_{false}; - bool is_loop_list_on_{false}; - - // QT Containers - QGroupBox * makeGoalsListGroup(); - QGroupBox * makeRoutingGroup(); - QGroupBox * makeEngagementGroup(); - QTimer * qt_timer_{nullptr}; - QListWidget * goals_list_widget_ptr_{nullptr}; - QLabel * routing_label_ptr_{nullptr}; - QLabel * operation_mode_label_ptr_{nullptr}; - QLabel * engagement_label_ptr_{nullptr}; - QPushButton * loop_list_btn_ptr_{nullptr}; - QPushButton * goals_achieved_btn_ptr_{nullptr}; - QPushButton * load_file_btn_ptr_{nullptr}; - QPushButton * save_file_btn_ptr_{nullptr}; - QPushButton * automatic_mode_btn_ptr_{nullptr}; - QPushButton * remove_selected_goal_btn_ptr_{nullptr}; - QPushButton * clear_route_btn_ptr_{nullptr}; - QPushButton * plan_btn_ptr_{nullptr}; - QPushButton * start_btn_ptr_{nullptr}; - QPushButton * stop_btn_ptr_{nullptr}; -}; -} // namespace rviz_plugins - -#endif // AUTOMATIC_GOAL_PANEL_HPP_ diff --git a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_sender.cpp b/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_sender.cpp deleted file mode 100644 index 3ca368a3bd1a4..0000000000000 --- a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_sender.cpp +++ /dev/null @@ -1,227 +0,0 @@ -// Copyright 2016 Open Source Robotics Foundation, 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 "automatic_goal_sender.hpp" - -namespace automatic_goal -{ -AutowareAutomaticGoalSender::AutowareAutomaticGoalSender() : Node("automatic_goal_sender") -{ -} - -void AutowareAutomaticGoalSender::init() -{ - loadParams(this); - initCommunication(this); - loadGoalsList(goals_list_file_path_); - timer_ = this->create_wall_timer( - std::chrono::milliseconds(500), - std::bind(&AutowareAutomaticGoalSender::updateAutoExecutionTimerTick, this)); - - // Print info - RCLCPP_INFO_STREAM(get_logger(), "GoalsList has been loaded from: " << goals_list_file_path_); - for (auto const & goal : goals_achieved_) - RCLCPP_INFO_STREAM(get_logger(), "Loaded: " << goal.second.first); - RCLCPP_INFO_STREAM( - get_logger(), "Achieved goals will be saved in: " << goals_achieved_file_path_); -} - -void AutowareAutomaticGoalSender::loadParams(rclcpp::Node * node) -{ - namespace fs = std::filesystem; - node->declare_parameter("goals_list_file_path", ""); - node->declare_parameter("goals_achieved_dir_path", ""); - // goals_list - goals_list_file_path_ = node->get_parameter("goals_list_file_path").as_string(); - if (!fs::exists(goals_list_file_path_) || !fs::is_regular_file(goals_list_file_path_)) - throw std::invalid_argument( - "goals_list_file_path parameter - file path is invalid: " + goals_list_file_path_); - // goals_achieved - goals_achieved_file_path_ = node->get_parameter("goals_achieved_dir_path").as_string(); - if (!fs::exists(goals_achieved_file_path_) || fs::is_regular_file(goals_achieved_file_path_)) - throw std::invalid_argument( - "goals_achieved_dir_path - directory path is invalid: " + goals_achieved_file_path_); - goals_achieved_file_path_ += "goals_achieved.log"; -} - -void AutowareAutomaticGoalSender::initCommunication(rclcpp::Node * node) -{ - // Executing - sub_operation_mode_ = node->create_subscription( - "/api/operation_mode/state", rclcpp::QoS{1}.transient_local(), - std::bind(&AutowareAutomaticGoalSender::onOperationMode, this, std::placeholders::_1)); - - cli_change_to_autonomous_ = - node->create_client("/api/operation_mode/change_to_autonomous"); - - cli_change_to_stop_ = - node->create_client("/api/operation_mode/change_to_stop"); - - // Planning - sub_route_ = node->create_subscription( - "/api/routing/state", rclcpp::QoS{1}.transient_local(), - std::bind(&AutowareAutomaticGoalSender::onRoute, this, std::placeholders::_1)); - - cli_clear_route_ = node->create_client("/api/routing/clear_route"); - - cli_set_route_ = node->create_client("/api/routing/set_route_points"); -} - -// Sub -void AutowareAutomaticGoalSender::onRoute(const RouteState::ConstSharedPtr msg) -{ - if (msg->state == RouteState::UNSET && state_ == State::CLEARING) - state_ = State::CLEARED; - else if (msg->state == RouteState::SET && state_ == State::PLANNING) - state_ = State::PLANNED; - else if (msg->state == RouteState::ARRIVED && state_ == State::STARTED) - state_ = State::ARRIVED; - onRouteUpdated(msg); -} - -void AutowareAutomaticGoalSender::onOperationMode(const OperationModeState::ConstSharedPtr msg) -{ - if (msg->mode == OperationModeState::STOP && state_ == State::INITIALIZING) - state_ = State::EDITING; - else if (msg->mode == OperationModeState::STOP && state_ == State::STOPPING) - state_ = State::STOPPED; - else if (msg->mode == OperationModeState::AUTONOMOUS && state_ == State::STARTING) - state_ = State::STARTED; - onOperationModeUpdated(msg); -} - -// Update -void AutowareAutomaticGoalSender::updateGoalsList() -{ - unsigned i = 0; - for (const auto & goal : goals_list_) { - std::stringstream ss; - ss << std::fixed << std::setprecision(2); - tf2::Quaternion tf2_quat; - tf2::convert(goal.goal_pose_ptr->pose.orientation, tf2_quat); - ss << "G" << i << " (" << goal.goal_pose_ptr->pose.position.x << ", "; - ss << goal.goal_pose_ptr->pose.position.y << ", " << tf2::getYaw(tf2_quat) << ")"; - goals_achieved_.insert({i++, std::make_pair(ss.str(), 0)}); - } - onGoalListUpdated(); -} - -void AutowareAutomaticGoalSender::updateAutoExecutionTimerTick() -{ - auto goal = goals_achieved_[current_goal_].first; - - if (state_ == State::INITIALIZING) { - RCLCPP_INFO_THROTTLE( - get_logger(), *get_clock(), 3000, "Initializing... waiting for OperationModeState::STOP"); - - } else if (state_ == State::EDITING) { // skip the editing step by default - state_ = State::AUTO_NEXT; - - } else if (state_ == State::AUTO_NEXT) { // plan to next goal - RCLCPP_INFO_STREAM(get_logger(), goal << ": Goal set as the next. Planning in progress..."); - if (callPlanToGoalIndex(cli_set_route_, current_goal_)) state_ = State::PLANNING; - - } else if (state_ == State::PLANNED) { // start plan to next goal - RCLCPP_INFO_STREAM(get_logger(), goal << ": Route has been planned. Route starting..."); - if (callService(cli_change_to_autonomous_)) state_ = State::STARTING; - - } else if (state_ == State::STARTED) { - RCLCPP_INFO_STREAM_THROTTLE(get_logger(), *get_clock(), 5000, goal << ": Driving to the goal."); - - } else if (state_ == State::ARRIVED) { // clear plan after achieving next goal, goal++ - RCLCPP_INFO_STREAM( - get_logger(), goal << ": Goal has been ACHIEVED " << ++goals_achieved_[current_goal_].second - << " times. Route clearing..."); - updateAchievedGoalsFile(current_goal_); - if (callService(cli_clear_route_)) state_ = State::CLEARING; - - } else if (state_ == State::CLEARED) { - RCLCPP_INFO_STREAM(get_logger(), goal << ": Route has been cleared."); - current_goal_++; - current_goal_ = current_goal_ % goals_list_.size(); - state_ = State::AUTO_NEXT; - - } else if (state_ == State::STOPPED) { - RCLCPP_WARN_STREAM( - get_logger(), goal << ": The execution has been stopped unexpectedly! Restarting..."); - if (callService(cli_change_to_autonomous_)) state_ = State::STARTING; - - } else if (state_ == State::ERROR) { - timer_->cancel(); - throw std::runtime_error(goal + ": Error encountered during execution!"); - } -} - -// File -void AutowareAutomaticGoalSender::loadGoalsList(const std::string & file_path) -{ - YAML::Node node = YAML::LoadFile(file_path); - goals_list_.clear(); - for (auto && goal : node) { - std::shared_ptr pose = std::make_shared(); - pose->header.frame_id = "map"; - pose->header.stamp = rclcpp::Time(); - pose->pose.position.x = goal["position_x"].as(); - pose->pose.position.y = goal["position_y"].as(); - pose->pose.position.z = goal["position_z"].as(); - pose->pose.orientation.x = goal["orientation_x"].as(); - pose->pose.orientation.y = goal["orientation_y"].as(); - pose->pose.orientation.z = goal["orientation_z"].as(); - pose->pose.orientation.w = goal["orientation_w"].as(); - goals_list_.emplace_back(pose); - } - resetAchievedGoals(); - updateGoalsList(); -} - -void AutowareAutomaticGoalSender::updateAchievedGoalsFile(const unsigned goal_index) -{ - if (!goals_achieved_file_path_.empty()) { - std::ofstream out(goals_achieved_file_path_, std::fstream::app); - std::stringstream ss; - ss << "[" << getTimestamp() << "] Achieved: " << goals_achieved_[goal_index].first; - ss << ", Current number of achievements: " << goals_achieved_[goal_index].second << "\n"; - out << ss.str(); - out.close(); - } -} - -void AutowareAutomaticGoalSender::resetAchievedGoals() -{ - goals_achieved_.clear(); - if (!goals_achieved_file_path_.empty()) { - std::ofstream out(goals_achieved_file_path_, std::fstream::app); - out << "[" << getTimestamp() - << "] GoalsList was loaded from a file or a goal was removed - counters have been reset\n"; - out.close(); - } -} -} // namespace automatic_goal - -int main(int argc, char * argv[]) -{ - rclcpp::init(argc, argv); - - std::shared_ptr node{nullptr}; - try { - node = std::make_shared(); - node->init(); - } catch (const std::exception & e) { - fprintf(stderr, "%s Exiting...\n", e.what()); - return 1; - } - - rclcpp::spin(node); - rclcpp::shutdown(); - return 0; -} diff --git a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_sender.hpp b/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_sender.hpp deleted file mode 100644 index 88b7b5e7dac20..0000000000000 --- a/common/tier4_automatic_goal_rviz_plugin/src/automatic_goal_sender.hpp +++ /dev/null @@ -1,184 +0,0 @@ -// Copyright 2016 Open Source Robotics Foundation, 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 AUTOMATIC_GOAL_SENDER_HPP_ -#define AUTOMATIC_GOAL_SENDER_HPP_ -#include - -#include -#include -#include -#include -#include -#include -#include - -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include - -namespace automatic_goal -{ -enum class AutomaticGoalState { - INITIALIZING, - EDITING, - PLANNING, - PLANNED, - STARTING, - STARTED, - ARRIVED, - AUTO_NEXT, - STOPPING, - STOPPED, - CLEARING, - CLEARED, - ERROR, -}; - -class AutowareAutomaticGoalSender : public rclcpp::Node -{ - using State = AutomaticGoalState; - using PoseStamped = geometry_msgs::msg::PoseStamped; - using OperationModeState = autoware_adapi_v1_msgs::msg::OperationModeState; - using ChangeOperationMode = autoware_adapi_v1_msgs::srv::ChangeOperationMode; - using RouteState = autoware_adapi_v1_msgs::msg::RouteState; - using SetRoutePoints = autoware_adapi_v1_msgs::srv::SetRoutePoints; - using ClearRoute = autoware_adapi_v1_msgs::srv::ClearRoute; - -public: - AutowareAutomaticGoalSender(); - void init(); - -protected: - void initCommunication(rclcpp::Node * node); - // Calls - bool callPlanToGoalIndex( - const rclcpp::Client::SharedPtr client, const unsigned goal_index) - { - if (!client->service_is_ready()) { - RCLCPP_WARN(get_logger(), "SetRoutePoints client is unavailable"); - return false; - } - - auto req = std::make_shared(); - req->header = goals_list_.at(goal_index).goal_pose_ptr->header; - req->goal = goals_list_.at(goal_index).goal_pose_ptr->pose; - for (const auto & checkpoint : goals_list_.at(goal_index).checkpoint_pose_ptrs) { - req->waypoints.push_back(checkpoint->pose); - } - client->async_send_request( - req, [this](typename rclcpp::Client::SharedFuture result) { - if (result.get()->status.code != 0) state_ = State::ERROR; - printCallResult(result); - onCallResult(); - }); - return true; - } - template - bool callService(const typename rclcpp::Client::SharedPtr client) - { - if (!client->service_is_ready()) { - RCLCPP_WARN(get_logger(), "Client is unavailable"); - return false; - } - - auto req = std::make_shared(); - client->async_send_request(req, [this](typename rclcpp::Client::SharedFuture result) { - if (result.get()->status.code != 0) state_ = State::ERROR; - printCallResult(result); - onCallResult(); - }); - return true; - } - template - void printCallResult(typename rclcpp::Client::SharedFuture result) - { - if (result.get()->status.code != 0) { - RCLCPP_ERROR( - get_logger(), "Service type \"%s\" status: %d, %s", typeid(T).name(), - result.get()->status.code, result.get()->status.message.c_str()); - } else { - RCLCPP_DEBUG( - get_logger(), "Service type \"%s\" status: %d, %s", typeid(T).name(), - result.get()->status.code, result.get()->status.message.c_str()); - } - } - - struct Route - { - explicit Route(const PoseStamped::ConstSharedPtr & goal) : goal_pose_ptr{goal} {} - PoseStamped::ConstSharedPtr goal_pose_ptr{}; - std::vector checkpoint_pose_ptrs{}; - }; - - // Update - void updateGoalsList(); - virtual void updateAutoExecutionTimerTick(); - - // File - void loadGoalsList(const std::string & file_path); - void updateAchievedGoalsFile(const unsigned goal_index); - void resetAchievedGoals(); - static std::string getTimestamp() - { - char buffer[128]; - std::time_t now = std::chrono::system_clock::to_time_t(std::chrono::system_clock::now()); - std::strftime(&buffer[0], sizeof(buffer), "%Y-%m-%d %H:%M:%S", std::localtime(&now)); - return std::string{buffer}; - } - - // Sub - void onRoute(const RouteState::ConstSharedPtr msg); - void onOperationMode(const OperationModeState::ConstSharedPtr msg); - - // Interface - virtual void onRouteUpdated(const RouteState::ConstSharedPtr) {} - virtual void onOperationModeUpdated(const OperationModeState::ConstSharedPtr) {} - virtual void onCallResult() {} - virtual void onGoalListUpdated() {} - - // Cli - rclcpp::Client::SharedPtr cli_change_to_autonomous_{nullptr}; - rclcpp::Client::SharedPtr cli_change_to_stop_{nullptr}; - rclcpp::Client::SharedPtr cli_clear_route_{nullptr}; - rclcpp::Client::SharedPtr cli_set_route_{nullptr}; - - // Containers - unsigned current_goal_{0}; - State state_{State::INITIALIZING}; - std::vector goals_list_{}; - std::map> goals_achieved_{}; - std::string goals_achieved_file_path_{}; - -private: - void loadParams(rclcpp::Node * node); - - // Sub - rclcpp::Subscription::SharedPtr sub_route_{nullptr}; - rclcpp::Subscription::SharedPtr sub_operation_mode_{nullptr}; - - // Containers - std::string goals_list_file_path_{}; - rclcpp::TimerBase::SharedPtr timer_{nullptr}; -}; -} // namespace automatic_goal -#endif // AUTOMATIC_GOAL_SENDER_HPP_ diff --git a/common/tier4_autoware_utils/include/tier4_autoware_utils/math/trigonometry.hpp b/common/tier4_autoware_utils/include/tier4_autoware_utils/math/trigonometry.hpp index 0c53a9e3941dd..4901e28472acb 100644 --- a/common/tier4_autoware_utils/include/tier4_autoware_utils/math/trigonometry.hpp +++ b/common/tier4_autoware_utils/include/tier4_autoware_utils/math/trigonometry.hpp @@ -15,6 +15,8 @@ #ifndef TIER4_AUTOWARE_UTILS__MATH__TRIGONOMETRY_HPP_ #define TIER4_AUTOWARE_UTILS__MATH__TRIGONOMETRY_HPP_ +#include + namespace tier4_autoware_utils { @@ -22,6 +24,8 @@ float sin(float radian); float cos(float radian); +std::pair sin_and_cos(float radian); + } // namespace tier4_autoware_utils #endif // TIER4_AUTOWARE_UTILS__MATH__TRIGONOMETRY_HPP_ 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/common/tier4_autoware_utils/src/math/trigonometry.cpp b/common/tier4_autoware_utils/src/math/trigonometry.cpp index 15f5c71012722..0ce65c7aa5bc8 100644 --- a/common/tier4_autoware_utils/src/math/trigonometry.cpp +++ b/common/tier4_autoware_utils/src/math/trigonometry.cpp @@ -49,4 +49,27 @@ float cos(float radian) return sin(radian + static_cast(tier4_autoware_utils::pi) / 2.f); } +std::pair sin_and_cos(float radian) +{ + constexpr float tmp = + (180.f / static_cast(tier4_autoware_utils::pi)) * (discrete_arcs_num_360 / 360.f); + const float degree = radian * tmp; + size_t idx = + (static_cast(std::round(degree)) % discrete_arcs_num_360 + discrete_arcs_num_360) % + discrete_arcs_num_360; + + if (idx < discrete_arcs_num_90) { + return {g_sin_table[idx], g_sin_table[discrete_arcs_num_90 - idx]}; + } else if (discrete_arcs_num_90 <= idx && idx < 2 * discrete_arcs_num_90) { + idx = 2 * discrete_arcs_num_90 - idx; + return {g_sin_table[idx], -g_sin_table[discrete_arcs_num_90 - idx]}; + } else if (2 * discrete_arcs_num_90 <= idx && idx < 3 * discrete_arcs_num_90) { + idx = idx - 2 * discrete_arcs_num_90; + return {-g_sin_table[idx], -g_sin_table[discrete_arcs_num_90 - idx]}; + } else { // 3 * discrete_arcs_num_90 <= idx && idx < 4 * discrete_arcs_num_90 + idx = 4 * discrete_arcs_num_90 - idx; + return {-g_sin_table[idx], g_sin_table[discrete_arcs_num_90 - idx]}; + } +} + } // namespace tier4_autoware_utils diff --git a/common/tier4_autoware_utils/test/src/math/test_trigonometry.cpp b/common/tier4_autoware_utils/test/src/math/test_trigonometry.cpp index 379418539841c..d7106fd823682 100644 --- a/common/tier4_autoware_utils/test/src/math/test_trigonometry.cpp +++ b/common/tier4_autoware_utils/test/src/math/test_trigonometry.cpp @@ -40,3 +40,13 @@ TEST(trigonometry, cos) tier4_autoware_utils::cos(x * static_cast(i))) < 10e-5); } } + +TEST(trigonometry, sin_and_cos) +{ + float x = 4.f * tier4_autoware_utils::pi / 128.f; + for (int i = 0; i < 128; i++) { + const auto sin_and_cos = tier4_autoware_utils::sin_and_cos(x * static_cast(i)); + EXPECT_TRUE(std::abs(std::sin(x * static_cast(i)) - sin_and_cos.first) < 10e-7); + EXPECT_TRUE(std::abs(std::cos(x * static_cast(i)) - sin_and_cos.second) < 10e-7); + } +} diff --git a/common/tier4_calibration_rviz_plugin/CMakeLists.txt b/common/tier4_calibration_rviz_plugin/CMakeLists.txt deleted file mode 100644 index 6b03fe92da0ee..0000000000000 --- a/common/tier4_calibration_rviz_plugin/CMakeLists.txt +++ /dev/null @@ -1,27 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(tier4_calibration_rviz_plugin) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -find_package(Qt5 REQUIRED Core Widgets) -set(QT_LIBRARIES Qt5::Widgets) -set(CMAKE_AUTOMOC ON) -set(CMAKE_INCLUDE_CURRENT_DIR ON) -add_definitions(-DQT_NO_KEYWORDS) - -ament_auto_add_library(${PROJECT_NAME} SHARED - src/accel_brake_map_calibrator_button_panel.cpp -) - -target_link_libraries(${PROJECT_NAME} - ${QT_LIBRARIES} -) - -# 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 - plugins -) diff --git a/common/tier4_calibration_rviz_plugin/package.xml b/common/tier4_calibration_rviz_plugin/package.xml deleted file mode 100644 index f422847d8cb70..0000000000000 --- a/common/tier4_calibration_rviz_plugin/package.xml +++ /dev/null @@ -1,29 +0,0 @@ - - - - tier4_calibration_rviz_plugin - 0.1.0 - The accel_brake_map_calibrator_button_panel package - Tomoya Kimura - Apache License 2.0 - - Tomoya Kimura - - ament_cmake_auto - autoware_cmake - - libqt5-core - libqt5-widgets - qtbase5-dev - rviz_common - std_msgs - tier4_vehicle_msgs - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - - diff --git a/common/tier4_calibration_rviz_plugin/plugins/plugin_description.xml b/common/tier4_calibration_rviz_plugin/plugins/plugin_description.xml deleted file mode 100644 index 82f35b934208c..0000000000000 --- a/common/tier4_calibration_rviz_plugin/plugins/plugin_description.xml +++ /dev/null @@ -1,9 +0,0 @@ - - - - execution button of accel brake map calibration. - - - 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 deleted file mode 100644 index 5c1c98488b0f6..0000000000000 --- a/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.cpp +++ /dev/null @@ -1,151 +0,0 @@ -// -// Copyright 2020 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 "accel_brake_map_calibrator_button_panel.hpp" - -#include "QFileDialog" -#include "QHBoxLayout" -#include "QLineEdit" -#include "QPainter" -#include "QPushButton" -#include "pluginlib/class_list_macros.hpp" -#include "rviz_common/display_context.hpp" - -#include -#include -#include -#include - -namespace tier4_calibration_rviz_plugin -{ -AccelBrakeMapCalibratorButtonPanel::AccelBrakeMapCalibratorButtonPanel(QWidget * parent) -: rviz_common::Panel(parent) -{ - topic_label_ = new QLabel("Topic name of update suggest "); - 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())); - - calibration_button_ = new QPushButton("Wait for subscribe topic"); - calibration_button_->setEnabled(false); - connect(calibration_button_, SIGNAL(clicked(bool)), SLOT(pushCalibrationButton())); - - status_label_ = new QLabel("Not Ready"); - status_label_->setAlignment(Qt::AlignCenter); - status_label_->setStyleSheet("QLabel { background-color : darkgray;}"); - - QSizePolicy q_size_policy(QSizePolicy::Expanding, QSizePolicy::Expanding); - calibration_button_->setSizePolicy(q_size_policy); - - auto * topic_layout = new QHBoxLayout; - topic_layout->addWidget(topic_label_); - topic_layout->addWidget(topic_edit_); - - auto * v_layout = new QVBoxLayout; - v_layout->addLayout(topic_layout); - v_layout->addWidget(calibration_button_); - v_layout->addWidget(status_label_); - - setLayout(v_layout); -} - -void AccelBrakeMapCalibratorButtonPanel::onInitialize() -{ - 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)); - - client_ = raw_node->create_client( - "/vehicle/calibration/accel_brake_map_calibrator/update_map_dir"); -} - -void AccelBrakeMapCalibratorButtonPanel::callbackUpdateSuggest( - const std_msgs::msg::Bool::ConstSharedPtr msg) -{ - if (after_calib_) { - return; - } - - if (msg->data) { - status_label_->setText("Ready"); - status_label_->setStyleSheet("QLabel { background-color : white;}"); - } else { - status_label_->setText("Ready (not recommended)"); - status_label_->setStyleSheet("QLabel { background-color : darkgray;}"); - } - calibration_button_->setText("push: start to accel/brake map calibration"); - calibration_button_->setEnabled(true); -} - -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)); - calibration_button_->setText("Wait for subscribe topic"); - calibration_button_->setEnabled(false); -} - -void AccelBrakeMapCalibratorButtonPanel::pushCalibrationButton() -{ - // lock button - calibration_button_->setEnabled(false); - - status_label_->setStyleSheet("QLabel { background-color : blue;}"); - status_label_->setText("executing calibration..."); - - std::thread thread([this] { - if (!client_->wait_for_service(std::chrono::seconds(1))) { - status_label_->setStyleSheet("QLabel { background-color : red;}"); - status_label_->setText("service server not found"); - - } else { - auto req = std::make_shared(); - req->path = ""; - client_->async_send_request( - req, [this]([[maybe_unused]] rclcpp::Client< - tier4_vehicle_msgs::srv::UpdateAccelBrakeMap>::SharedFuture result) {}); - - status_label_->setStyleSheet("QLabel { background-color : lightgreen;}"); - status_label_->setText("OK!!!"); - } - - // wait 3 second - after_calib_ = true; - rclcpp::Rate(1.0 / 3.0).sleep(); - after_calib_ = false; - - // unlock button - calibration_button_->setEnabled(true); - }); - - thread.detach(); -} - -} // namespace tier4_calibration_rviz_plugin - -PLUGINLIB_EXPORT_CLASS( - tier4_calibration_rviz_plugin::AccelBrakeMapCalibratorButtonPanel, rviz_common::Panel) 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 deleted file mode 100644 index e26789c9f120f..0000000000000 --- a/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.hpp +++ /dev/null @@ -1,65 +0,0 @@ -// -// Copyright 2020 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 ACCEL_BRAKE_MAP_CALIBRATOR_BUTTON_PANEL_HPP_ -#define ACCEL_BRAKE_MAP_CALIBRATOR_BUTTON_PANEL_HPP_ - -#include "QLabel" -#include "QLineEdit" -#include "QPushButton" -#include "QSettings" - -#include -#ifndef Q_MOC_RUN - -#include "rclcpp/rclcpp.hpp" -#include "rviz_common/panel.hpp" -#include "rviz_common/properties/ros_topic_property.hpp" -#endif - -#include "std_msgs/msg/bool.hpp" -#include "tier4_vehicle_msgs/srv/update_accel_brake_map.hpp" - -namespace tier4_calibration_rviz_plugin -{ -class AccelBrakeMapCalibratorButtonPanel : public rviz_common::Panel -{ - Q_OBJECT - -public: - explicit AccelBrakeMapCalibratorButtonPanel(QWidget * parent = nullptr); - void onInitialize() override; - void callbackUpdateSuggest(const std_msgs::msg::Bool::ConstSharedPtr msg); - -public Q_SLOTS: // NOLINT for Qt - void editTopic(); - void pushCalibrationButton(); - -protected: - rclcpp::Subscription::SharedPtr update_suggest_sub_; - rclcpp::Client::SharedPtr client_; - - bool after_calib_ = false; - - QLabel * topic_label_; - QLineEdit * topic_edit_; - QPushButton * calibration_button_; - QLabel * status_label_; -}; - -} // end namespace tier4_calibration_rviz_plugin - -#endif // ACCEL_BRAKE_MAP_CALIBRATOR_BUTTON_PANEL_HPP_ diff --git a/common/tier4_control_rviz_plugin/CMakeLists.txt b/common/tier4_control_rviz_plugin/CMakeLists.txt deleted file mode 100644 index 95fff455991ba..0000000000000 --- a/common/tier4_control_rviz_plugin/CMakeLists.txt +++ /dev/null @@ -1,34 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(tier4_control_rviz_plugin) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -find_package(Qt5 REQUIRED Core Widgets) -set(QT_LIBRARIES Qt5::Widgets) - -set(CMAKE_AUTOMOC ON) -set(CMAKE_INCLUDE_CURRENT_DIR ON) -add_definitions(-DQT_NO_KEYWORDS) - -set(HEADERS - src/tools/manual_controller.hpp -) - -## Declare a C++ library -ament_auto_add_library(tier4_control_rviz_plugin SHARED - src/tools/manual_controller.cpp - ${HEADERS} -) - -target_link_libraries(tier4_control_rviz_plugin - ${QT_LIBRARIES} -) - -# 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 - plugins -) diff --git a/common/tier4_control_rviz_plugin/README.md b/common/tier4_control_rviz_plugin/README.md deleted file mode 100644 index 8bca77771eee2..0000000000000 --- a/common/tier4_control_rviz_plugin/README.md +++ /dev/null @@ -1,40 +0,0 @@ -# tier4_control_rviz_plugin - -This package is to mimic external control for simulation. - -## Inputs / Outputs - -### Input - -| Name | Type | Description | -| --------------------------------- | ------------------------------------------------- | ----------------------- | -| `/control/current_gate_mode` | `tier4_control_msgs::msg::GateMode` | Current GATE mode | -| `/vehicle/status/velocity_status` | `autoware_auto_vehicle_msgs::msg::VelocityReport` | Current velocity status | -| `/api/autoware/get/engage` | `tier4_external_api_msgs::srv::Engage` | Getting Engage | -| `/vehicle/status/gear_status` | `autoware_auto_vehicle_msgs::msg::GearReport` | The state of GEAR | - -### Output - -| Name | Type | Description | -| -------------------------------- | ---------------------------------------------------------- | ----------------------- | -| `/control/gate_mode_cmd` | `tier4_control_msgs::msg::GateMode` | GATE mode | -| `/external/selected/control_cmd` | `autoware_auto_control_msgs::msg::AckermannControlCommand` | AckermannControlCommand | -| `/external/selected/gear_cmd` | `autoware_auto_vehicle_msgs::msg::GearCommand` | GEAR | - -## Usage - -1. Start rviz and select Panels. - - ![select_panels](./images/select_panels.png) - -2. Select tier4_control_rviz_plugin/ManualController and press OK. - - ![select_manual_controller](./images/select_manual_controller.png) - -3. Enter velocity in "Set Cruise Velocity" and Press the button to confirm. You can notice that GEAR shows D (DRIVE). - - ![manual_controller_not_ready](./images/manual_controller_not_ready.png) - -4. Press "Enable Manual Control" and you can notice that "GATE" and "Engage" turn "Ready" and the vehicle starts! - - ![manual_controller_ready](./images/manual_controller_ready.png) diff --git a/common/tier4_control_rviz_plugin/images/manual_controller_not_ready.png b/common/tier4_control_rviz_plugin/images/manual_controller_not_ready.png deleted file mode 100644 index e4a8ddb0b9bb1..0000000000000 Binary files a/common/tier4_control_rviz_plugin/images/manual_controller_not_ready.png and /dev/null differ diff --git a/common/tier4_control_rviz_plugin/images/manual_controller_ready.png b/common/tier4_control_rviz_plugin/images/manual_controller_ready.png deleted file mode 100644 index d5da7f0644051..0000000000000 Binary files a/common/tier4_control_rviz_plugin/images/manual_controller_ready.png and /dev/null differ diff --git a/common/tier4_control_rviz_plugin/images/select_manual_controller.png b/common/tier4_control_rviz_plugin/images/select_manual_controller.png deleted file mode 100644 index 5027ec571339c..0000000000000 Binary files a/common/tier4_control_rviz_plugin/images/select_manual_controller.png and /dev/null differ diff --git a/common/tier4_control_rviz_plugin/images/select_panels.png b/common/tier4_control_rviz_plugin/images/select_panels.png deleted file mode 100644 index a691602c42c3c..0000000000000 Binary files a/common/tier4_control_rviz_plugin/images/select_panels.png and /dev/null differ diff --git a/common/tier4_control_rviz_plugin/package.xml b/common/tier4_control_rviz_plugin/package.xml deleted file mode 100644 index 73562a766ce0b..0000000000000 --- a/common/tier4_control_rviz_plugin/package.xml +++ /dev/null @@ -1,32 +0,0 @@ - - - - tier4_control_rviz_plugin - 0.1.0 - The tier4_vehicle_rviz_plugin package - Taiki Tanaka - Apache License 2.0 - - ament_cmake_auto - autoware_cmake - - autoware_auto_control_msgs - autoware_auto_vehicle_msgs - libqt5-core - libqt5-gui - libqt5-widgets - qtbase5-dev - rviz_common - rviz_default_plugins - rviz_ogre_vendor - tier4_autoware_utils - tier4_control_msgs - tier4_external_api_msgs - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - diff --git a/common/tier4_control_rviz_plugin/plugins/plugin_description.xml b/common/tier4_control_rviz_plugin/plugins/plugin_description.xml deleted file mode 100644 index 068bbcd73f214..0000000000000 --- a/common/tier4_control_rviz_plugin/plugins/plugin_description.xml +++ /dev/null @@ -1,7 +0,0 @@ - - - ManualController - - diff --git a/common/tier4_control_rviz_plugin/src/tools/manual_controller.cpp b/common/tier4_control_rviz_plugin/src/tools/manual_controller.cpp deleted file mode 100644 index 8bbb096f728ec..0000000000000 --- a/common/tier4_control_rviz_plugin/src/tools/manual_controller.cpp +++ /dev/null @@ -1,261 +0,0 @@ -// -// Copyright 2022 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 "manual_controller.hpp" - -#include -#include -#include -#include -#include - -#include -#include - -using std::placeholders::_1; - -namespace rviz_plugins -{ - -ManualController::ManualController(QWidget * parent) : rviz_common::Panel(parent) -{ - auto * state_layout = new QHBoxLayout; - { - // Enable Button - enable_button_ptr_ = new QPushButton("Enable Manual Control"); - connect(enable_button_ptr_, SIGNAL(clicked()), SLOT(onClickEnableButton())); - state_layout->addWidget(enable_button_ptr_); - - // Gate Mode - auto * gate_prefix_label_ptr = new QLabel("GATE: "); - gate_prefix_label_ptr->setAlignment(Qt::AlignRight); - gate_mode_label_ptr_ = new QLabel("INIT"); - gate_mode_label_ptr_->setAlignment(Qt::AlignCenter); - state_layout->addWidget(gate_prefix_label_ptr); - state_layout->addWidget(gate_mode_label_ptr_); - - // Engage Status - auto * engage_prefix_label_ptr = new QLabel("Engage: "); - engage_prefix_label_ptr->setAlignment(Qt::AlignRight); - engage_status_label_ptr_ = new QLabel("INIT"); - engage_status_label_ptr_->setAlignment(Qt::AlignCenter); - state_layout->addWidget(engage_prefix_label_ptr); - state_layout->addWidget(engage_status_label_ptr_); - - // Gear - auto * gear_prefix_label_ptr = new QLabel("GEAR: "); - gear_prefix_label_ptr->setAlignment(Qt::AlignRight); - gear_label_ptr_ = new QLabel("INIT"); - gear_label_ptr_->setAlignment(Qt::AlignCenter); - state_layout->addWidget(gear_prefix_label_ptr); - state_layout->addWidget(gear_label_ptr_); - } - - auto * cruise_velocity_layout = new QHBoxLayout(); - // Velocity Limit - { - cruise_velocity_button_ptr_ = new QPushButton("Set Cruise Velocity"); - cruise_velocity_input_ = new QSpinBox(); - cruise_velocity_input_->setRange(-100.0, 100.0); - cruise_velocity_input_->setValue(0.0); - cruise_velocity_input_->setSingleStep(5.0); - connect(cruise_velocity_button_ptr_, SIGNAL(clicked()), this, SLOT(onClickCruiseVelocity())); - cruise_velocity_layout->addWidget(cruise_velocity_button_ptr_); - cruise_velocity_layout->addWidget(cruise_velocity_input_); - cruise_velocity_layout->addWidget(new QLabel(" [km/h]")); - } - - steering_slider_ptr_ = new QDial(); - steering_slider_ptr_->setRange(-90, 90); - steering_slider_ptr_->setValue(0.0); - connect(steering_slider_ptr_, SIGNAL(valueChanged(int)), this, SLOT(onManualSteering())); - steering_angle_ptr_ = new QLabel(); - cruise_velocity_layout->addWidget(new QLabel("steering ")); - cruise_velocity_layout->addWidget(steering_slider_ptr_); - cruise_velocity_layout->addWidget(steering_angle_ptr_); - cruise_velocity_layout->addWidget(new QLabel(" [deg]")); - - // Layout - auto * v_layout = new QVBoxLayout; - v_layout->addLayout(state_layout); - v_layout->addLayout(cruise_velocity_layout); - setLayout(v_layout); - - auto * timer = new QTimer(this); - connect(timer, &QTimer::timeout, this, &ManualController::update); - timer->start(30); -} - -void ManualController::update() -{ - if (!raw_node_) return; - AckermannControlCommand ackermann; - { - ackermann.stamp = raw_node_->get_clock()->now(); - ackermann.lateral.steering_tire_angle = steering_angle_; - ackermann.longitudinal.speed = cruise_velocity_; - /** - * @brief Calculate desired acceleration by simple BackSteppingControl - * V = 0.5*(v-v_des)^2 >= 0 - * D[V] = (D[v] - a_des)*(v-v_des) <=0 - * a_des = k_const *(v - v_des) + a (k < 0 ) - */ - const double k = -0.5; - const double v = current_velocity_; - const double v_des = cruise_velocity_; - const double a = current_acceleration_; - const double a_des = k * (v - v_des) + a; - ackermann.longitudinal.acceleration = std::clamp(a_des, -1.0, 1.0); - } - GearCommand gear_cmd; - { - const double eps = 0.001; - if (ackermann.longitudinal.speed > eps && current_velocity_ > -eps) { - gear_cmd.command = GearCommand::DRIVE; - } else if (ackermann.longitudinal.speed < -eps && current_velocity_ < eps) { - gear_cmd.command = GearCommand::REVERSE; - ackermann.longitudinal.acceleration *= -1.0; - } else { - gear_cmd.command = GearCommand::PARK; - } - } - pub_control_command_->publish(ackermann); - pub_gear_cmd_->publish(gear_cmd); -} - -void ManualController::onManualSteering() -{ - const double scale_factor = -0.25; - steering_angle_ = scale_factor * steering_slider_ptr_->sliderPosition() * M_PI / 180.0; - const QString steering_string = - QString::fromStdString(std::to_string(steering_angle_ * 180.0 / M_PI)); - steering_angle_ptr_->setText(steering_string); -} - -void ManualController::onClickCruiseVelocity() -{ - cruise_velocity_ = cruise_velocity_input_->value() / 3.6; -} - -void ManualController::onInitialize() -{ - raw_node_ = this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); - - sub_gate_mode_ = raw_node_->create_subscription( - "/control/current_gate_mode", 10, std::bind(&ManualController::onGateMode, this, _1)); - - sub_velocity_ = raw_node_->create_subscription( - "/vehicle/status/velocity_status", 1, std::bind(&ManualController::onVelocity, this, _1)); - - sub_engage_ = raw_node_->create_subscription( - "/api/autoware/get/engage", 10, std::bind(&ManualController::onEngageStatus, this, _1)); - - sub_gear_ = raw_node_->create_subscription( - "/vehicle/status/gear_status", 10, std::bind(&ManualController::onGear, this, _1)); - - client_engage_ = raw_node_->create_client("/api/autoware/set/engage"); - - pub_gate_mode_ = raw_node_->create_publisher("/control/gate_mode_cmd", rclcpp::QoS(1)); - - pub_control_command_ = raw_node_->create_publisher( - "/external/selected/control_cmd", rclcpp::QoS(1)); - - pub_gear_cmd_ = raw_node_->create_publisher("/external/selected/gear_cmd", 1); -} - -void ManualController::onGateMode(const tier4_control_msgs::msg::GateMode::ConstSharedPtr msg) -{ - switch (msg->data) { - case tier4_control_msgs::msg::GateMode::AUTO: - gate_mode_label_ptr_->setText("Not Ready"); - gate_mode_label_ptr_->setStyleSheet("background-color: #00FF00;"); - break; - - case tier4_control_msgs::msg::GateMode::EXTERNAL: - gate_mode_label_ptr_->setText("Ready"); - gate_mode_label_ptr_->setStyleSheet("background-color: #FFFF00;"); - break; - - default: - gate_mode_label_ptr_->setText("UNKNOWN"); - gate_mode_label_ptr_->setStyleSheet("background-color: #FF0000;"); - break; - } -} -void ManualController::onEngageStatus(const Engage::ConstSharedPtr msg) -{ - current_engage_ = msg->engage; - if (current_engage_) { - engage_status_label_ptr_->setText(QString::fromStdString("Ready")); - engage_status_label_ptr_->setStyleSheet("background-color: #FFFF00;"); - } else { - engage_status_label_ptr_->setText(QString::fromStdString("Not Ready")); - engage_status_label_ptr_->setStyleSheet("background-color: #00FF00;"); - } -} - -void ManualController::onVelocity(const VelocityReport::ConstSharedPtr msg) -{ - current_velocity_ = msg->longitudinal_velocity; -} - -void ManualController::onAcceleration(const AccelWithCovarianceStamped::ConstSharedPtr msg) -{ - current_acceleration_ = msg->accel.accel.linear.x; -} - -void ManualController::onGear(const GearReport::ConstSharedPtr msg) -{ - switch (msg->report) { - case GearReport::PARK: - gear_label_ptr_->setText("P"); - break; - case GearReport::REVERSE: - gear_label_ptr_->setText("R"); - break; - case GearReport::DRIVE: - gear_label_ptr_->setText("D"); - break; - case GearReport::LOW: - gear_label_ptr_->setText("L"); - break; - } -} - -void ManualController::onClickEnableButton() -{ - // gate mode - { - pub_gate_mode_->publish(tier4_control_msgs::build().data(GateMode::EXTERNAL)); - } - // engage - { - auto req = std::make_shared(); - req->engage = true; - RCLCPP_DEBUG(raw_node_->get_logger(), "client request"); - if (!client_engage_->service_is_ready()) { - RCLCPP_DEBUG(raw_node_->get_logger(), "client is unavailable"); - return; - } - client_engage_->async_send_request( - req, []([[maybe_unused]] rclcpp::Client::SharedFuture result) {}); - } -} - -} // namespace rviz_plugins - -#include -PLUGINLIB_EXPORT_CLASS(rviz_plugins::ManualController, rviz_common::Panel) diff --git a/common/tier4_control_rviz_plugin/src/tools/manual_controller.hpp b/common/tier4_control_rviz_plugin/src/tools/manual_controller.hpp deleted file mode 100644 index aaa625bff911e..0000000000000 --- a/common/tier4_control_rviz_plugin/src/tools/manual_controller.hpp +++ /dev/null @@ -1,104 +0,0 @@ -// -// Copyright 2022 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 TOOLS__MANUAL_CONTROLLER_HPP_ -#define TOOLS__MANUAL_CONTROLLER_HPP_ - -#include -#include -#include -#include -#include -#include - -#include "autoware_auto_vehicle_msgs/msg/velocity_report.hpp" -#include "geometry_msgs/msg/accel_with_covariance_stamped.hpp" -#include "geometry_msgs/msg/twist.hpp" -#include -#include -#include -#include -#include -#include - -#include - -namespace rviz_plugins -{ -using autoware_auto_control_msgs::msg::AckermannControlCommand; -using autoware_auto_vehicle_msgs::msg::GearCommand; -using autoware_auto_vehicle_msgs::msg::VelocityReport; -using geometry_msgs::msg::AccelWithCovarianceStamped; -using geometry_msgs::msg::Twist; -using tier4_control_msgs::msg::GateMode; -using EngageSrv = tier4_external_api_msgs::srv::Engage; -using autoware_auto_vehicle_msgs::msg::Engage; -using autoware_auto_vehicle_msgs::msg::GearReport; - -class ManualController : public rviz_common::Panel -{ - Q_OBJECT - -public: - explicit ManualController(QWidget * parent = nullptr); - void onInitialize() override; - -public Q_SLOTS: // NOLINT for Qt - void onClickCruiseVelocity(); - void onClickEnableButton(); - void onManualSteering(); - void update(); - -protected: - // Timer - rclcpp::TimerBase::SharedPtr timer_; - void onTimer(); - void onPublishControlCommand(); - void onGateMode(const GateMode::ConstSharedPtr msg); - void onVelocity(const VelocityReport::ConstSharedPtr msg); - void onAcceleration(const AccelWithCovarianceStamped::ConstSharedPtr msg); - void onEngageStatus(const Engage::ConstSharedPtr msg); - void onGear(const GearReport::ConstSharedPtr msg); - rclcpp::Node::SharedPtr raw_node_; - rclcpp::Subscription::SharedPtr sub_gate_mode_; - rclcpp::Subscription::SharedPtr sub_velocity_; - rclcpp::Subscription::SharedPtr sub_engage_; - rclcpp::Publisher::SharedPtr pub_gate_mode_; - rclcpp::Publisher::SharedPtr pub_control_command_; - rclcpp::Publisher::SharedPtr pub_gear_cmd_; - rclcpp::Client::SharedPtr client_engage_; - rclcpp::Subscription::SharedPtr sub_gear_; - - double cruise_velocity_{0.0}; - double steering_angle_{0.0}; - double current_velocity_{0.0}; - double current_acceleration_{0.0}; - - QLabel * gate_mode_label_ptr_; - QLabel * gear_label_ptr_; - QLabel * engage_status_label_ptr_; - QPushButton * enable_button_ptr_; - QPushButton * cruise_velocity_button_ptr_; - QSpinBox * cruise_velocity_input_; - QDial * steering_slider_ptr_; - QLabel * steering_angle_ptr_; - - bool current_engage_{false}; -}; - -} // namespace rviz_plugins - -#endif // TOOLS__MANUAL_CONTROLLER_HPP_ diff --git a/common/tier4_debug_rviz_plugin/CMakeLists.txt b/common/tier4_debug_rviz_plugin/CMakeLists.txt deleted file mode 100644 index 02e65ad759ed6..0000000000000 --- a/common/tier4_debug_rviz_plugin/CMakeLists.txt +++ /dev/null @@ -1,32 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(tier4_debug_rviz_plugin) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -find_package(Qt5 REQUIRED Core Widgets) -set(QT_LIBRARIES Qt5::Widgets) -set(CMAKE_AUTOMOC ON) -add_definitions(-DQT_NO_KEYWORDS) - -ament_auto_add_library(tier4_debug_rviz_plugin SHARED - include/tier4_debug_rviz_plugin/float32_multi_array_stamped_pie_chart.hpp - include/tier4_debug_rviz_plugin/jsk_overlay_utils.hpp - include/tier4_debug_rviz_plugin/string_stamped.hpp - src/float32_multi_array_stamped_pie_chart.cpp - src/string_stamped.cpp - src/jsk_overlay_utils.cpp -) - -target_link_libraries(tier4_debug_rviz_plugin - ${QT_LIBRARIES} -) - -# 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/common/tier4_debug_rviz_plugin/README.md b/common/tier4_debug_rviz_plugin/README.md deleted file mode 100644 index 9189816141632..0000000000000 --- a/common/tier4_debug_rviz_plugin/README.md +++ /dev/null @@ -1,12 +0,0 @@ -# tier4_debug_rviz_plugin - -This package is including jsk code. -Note that jsk_overlay_utils.cpp and jsk_overlay_utils.hpp are BSD license. - -## Plugins - -### Float32MultiArrayStampedPieChart - -Pie chart from `tier4_debug_msgs::msg::Float32MultiArrayStamped`. - -![float32_multi_array_stamped_pie_chart](./images/float32_multi_array_stamped_pie_chart.png) diff --git a/common/tier4_debug_rviz_plugin/icons/classes/Float32MultiArrayStampedPieChart.png b/common/tier4_debug_rviz_plugin/icons/classes/Float32MultiArrayStampedPieChart.png deleted file mode 100644 index 6a67573717ae1..0000000000000 Binary files a/common/tier4_debug_rviz_plugin/icons/classes/Float32MultiArrayStampedPieChart.png and /dev/null differ diff --git a/common/tier4_debug_rviz_plugin/icons/classes/StringStampedOverlayDisplay.png b/common/tier4_debug_rviz_plugin/icons/classes/StringStampedOverlayDisplay.png deleted file mode 100644 index 6a67573717ae1..0000000000000 Binary files a/common/tier4_debug_rviz_plugin/icons/classes/StringStampedOverlayDisplay.png and /dev/null differ diff --git a/common/tier4_debug_rviz_plugin/images/float32_multi_array_stamped_pie_chart.png b/common/tier4_debug_rviz_plugin/images/float32_multi_array_stamped_pie_chart.png deleted file mode 100644 index 7cd7ca753f386..0000000000000 Binary files a/common/tier4_debug_rviz_plugin/images/float32_multi_array_stamped_pie_chart.png and /dev/null differ diff --git a/common/tier4_debug_rviz_plugin/include/tier4_debug_rviz_plugin/float32_multi_array_stamped_pie_chart.hpp b/common/tier4_debug_rviz_plugin/include/tier4_debug_rviz_plugin/float32_multi_array_stamped_pie_chart.hpp deleted file mode 100644 index c8267c7051d9d..0000000000000 --- a/common/tier4_debug_rviz_plugin/include/tier4_debug_rviz_plugin/float32_multi_array_stamped_pie_chart.hpp +++ /dev/null @@ -1,172 +0,0 @@ -// 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. - -// Copyright (c) 2014, JSK Lab -// All rights reserved. -// -// Software License Agreement (BSD License) -// -// 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 {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 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.S SOFTWARE, EVEN IF ADVISED OF THE -// POSSIBILITY OF SUCH DAMAGE. - -#ifndef TIER4_DEBUG_RVIZ_PLUGIN__FLOAT32_MULTI_ARRAY_STAMPED_PIE_CHART_HPP_ -#define TIER4_DEBUG_RVIZ_PLUGIN__FLOAT32_MULTI_ARRAY_STAMPED_PIE_CHART_HPP_ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -#include - -namespace rviz_plugins -{ -class Float32MultiArrayStampedPieChartDisplay : public rviz_common::Display -{ - Q_OBJECT -public: - Float32MultiArrayStampedPieChartDisplay(); - virtual ~Float32MultiArrayStampedPieChartDisplay(); - - // methods for OverlayPickerTool - virtual bool isInRegion(int x, int y); - virtual void movePosition(int x, int y); - virtual void setPosition(int x, int y); - virtual int getX() { return left_; } - virtual int getY() { return top_; } - -protected: - virtual void subscribe(); - virtual void unsubscribe(); - virtual void onEnable(); - virtual void onDisable(); - virtual void onInitialize(); - virtual void processMessage( - const tier4_debug_msgs::msg::Float32MultiArrayStamped::ConstSharedPtr msg); - virtual void drawPlot(double val); - virtual void update(float wall_dt, float ros_dt); - // properties - rviz_common::properties::StringProperty * update_topic_property_; - rviz_common::properties::IntProperty * data_index_property_; - rviz_common::properties::IntProperty * size_property_; - rviz_common::properties::IntProperty * left_property_; - rviz_common::properties::IntProperty * top_property_; - rviz_common::properties::ColorProperty * fg_color_property_; - rviz_common::properties::ColorProperty * bg_color_property_; - rviz_common::properties::ColorProperty * text_color_property_; - rviz_common::properties::FloatProperty * fg_alpha_property_; - rviz_common::properties::FloatProperty * fg_alpha2_property_; - rviz_common::properties::FloatProperty * bg_alpha_property_; - rviz_common::properties::FloatProperty * text_alpha_property_; - rviz_common::properties::IntProperty * text_size_property_; - rviz_common::properties::FloatProperty * max_value_property_; - rviz_common::properties::FloatProperty * min_value_property_; - rviz_common::properties::BoolProperty * show_caption_property_; - rviz_common::properties::BoolProperty * auto_color_change_property_; - rviz_common::properties::ColorProperty * max_color_property_; - rviz_common::properties::ColorProperty * med_color_property_; - rviz_common::properties::FloatProperty * max_color_threshold_property_; - rviz_common::properties::FloatProperty * med_color_threshold_property_; - rviz_common::properties::BoolProperty * clockwise_rotate_property_; - - rclcpp::Subscription::SharedPtr sub_; - int left_; - int top_; - uint16_t texture_size_; - QColor fg_color_; - QColor bg_color_; - QColor max_color_; - QColor med_color_; - int text_size_; - bool show_caption_; - bool auto_color_change_; - int caption_offset_; - double fg_alpha_; - double fg_alpha2_; - double bg_alpha_; - double max_value_; - double min_value_; - double max_color_threshold_; - double med_color_threshold_; - bool update_required_; - bool first_time_; - float data_; - int data_index_{0}; - jsk_rviz_plugins::OverlayObject::Ptr overlay_; - bool clockwise_rotate_; - - std::mutex mutex_; - -protected Q_SLOTS: - void updateTopic(); - void updateDataIndex(); - void updateSize(); - void updateTop(); - void updateLeft(); - void updateBGColor(); - void updateTextSize(); - void updateFGColor(); - void updateFGAlpha(); - void updateFGAlpha2(); - void updateBGAlpha(); - void updateMinValue(); - void updateMaxValue(); - void updateShowCaption(); - void updateAutoColorChange(); - void updateMaxColor(); - void updateMedColor(); - void updateMaxColorThreshold(); - void updateMedColorThreshold(); - void updateClockwiseRotate(); - -private: -}; - -} // namespace rviz_plugins - -#endif // TIER4_DEBUG_RVIZ_PLUGIN__FLOAT32_MULTI_ARRAY_STAMPED_PIE_CHART_HPP_ diff --git a/common/tier4_debug_rviz_plugin/include/tier4_debug_rviz_plugin/jsk_overlay_utils.hpp b/common/tier4_debug_rviz_plugin/include/tier4_debug_rviz_plugin/jsk_overlay_utils.hpp deleted file mode 100644 index 37bf743e35f6a..0000000000000 --- a/common/tier4_debug_rviz_plugin/include/tier4_debug_rviz_plugin/jsk_overlay_utils.hpp +++ /dev/null @@ -1,143 +0,0 @@ -// 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. - -// Copyright (c) 2014, JSK Lab -// All rights reserved. -// -// Software License Agreement (BSD License) -// -// 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 {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 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.S SOFTWARE, EVEN IF ADVISED OF THE -// POSSIBILITY OF SUCH DAMAGE. - -#ifndef TIER4_DEBUG_RVIZ_PLUGIN__JSK_OVERLAY_UTILS_HPP_ -#define TIER4_DEBUG_RVIZ_PLUGIN__JSK_OVERLAY_UTILS_HPP_ - -#include -#include -#include -#include -#include -#include - -#include -#include -// see OGRE/OgrePrerequisites.h -// #define OGRE_VERSION -// ((OGRE_VERSION_MAJOR << 16) | (OGRE_VERSION_MINOR << 8) | OGRE_VERSION_PATCH) -#if OGRE_VERSION < ((1 << 16) | (9 << 8) | 0) -#include -#include -#include -#include -#else -#include -#include -#include -#include -#include -#endif - -#include -#include -#include -#include -#include -#include - -namespace jsk_rviz_plugins -{ -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_; - -private: -}; - -// this is a class for put overlay object on rviz 3D panel. -// This class suppose to be instantiated in onInitialize method -// of rviz::Display class. -class OverlayObject -{ -public: - typedef std::shared_ptr Ptr; - - OverlayObject(Ogre::SceneManager * manager, rclcpp::Logger logger, const std::string & name); - virtual ~OverlayObject(); - - virtual std::string getName(); - virtual void hide(); - virtual void show(); - virtual bool isTextureReady(); - virtual void updateTextureSize(unsigned int width, unsigned int height); - virtual ScopedPixelBuffer getBuffer(); - virtual void setPosition(double left, double top); - virtual void setDimensions(double width, double height); - virtual bool isVisible(); - virtual unsigned int getTextureWidth(); - virtual unsigned int getTextureHeight(); - -protected: - const std::string name_; - rclcpp::Logger logger_; - Ogre::Overlay * overlay_; - Ogre::PanelOverlayElement * panel_; - Ogre::MaterialPtr panel_material_; - Ogre::TexturePtr texture_; - -private: -}; - -// Ogre::Overlay* createOverlay(std::string name); -// Ogre::PanelOverlayElement* createOverlayPanel(Ogre::Overlay* overlay); -// Ogre::MaterialPtr createOverlayMaterial(Ogre::Overlay* overlay); -} // namespace jsk_rviz_plugins - -#endif // TIER4_DEBUG_RVIZ_PLUGIN__JSK_OVERLAY_UTILS_HPP_ diff --git a/common/tier4_debug_rviz_plugin/include/tier4_debug_rviz_plugin/string_stamped.hpp b/common/tier4_debug_rviz_plugin/include/tier4_debug_rviz_plugin/string_stamped.hpp deleted file mode 100644 index 0960875d7eee2..0000000000000 --- a/common/tier4_debug_rviz_plugin/include/tier4_debug_rviz_plugin/string_stamped.hpp +++ /dev/null @@ -1,107 +0,0 @@ -// 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. - -// Copyright (c) 2014, JSK Lab -// All rights reserved. -// -// Software License Agreement (BSD License) -// -// 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 {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 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.S SOFTWARE, EVEN IF ADVISED OF THE -// POSSIBILITY OF SUCH DAMAGE. - -#ifndef TIER4_DEBUG_RVIZ_PLUGIN__STRING_STAMPED_HPP_ -#define TIER4_DEBUG_RVIZ_PLUGIN__STRING_STAMPED_HPP_ - -#include -#include - -#ifndef Q_MOC_RUN -#include "tier4_debug_rviz_plugin/jsk_overlay_utils.hpp" - -#include -#include -#include -#include - -#endif - -#include - -namespace rviz_plugins -{ -class StringStampedOverlayDisplay -: public rviz_common::RosTopicDisplay - -{ - Q_OBJECT - -public: - StringStampedOverlayDisplay(); - ~StringStampedOverlayDisplay() override; - - void onInitialize() override; - void onEnable() override; - void onDisable() override; - -private Q_SLOTS: - void updateVisualization(); - -protected: - void update(float wall_dt, float ros_dt) override; - void processMessage(const tier4_debug_msgs::msg::StringStamped::ConstSharedPtr msg_ptr) override; - jsk_rviz_plugins::OverlayObject::Ptr overlay_; - rviz_common::properties::ColorProperty * property_text_color_; - rviz_common::properties::IntProperty * property_left_; - rviz_common::properties::IntProperty * property_top_; - rviz_common::properties::IntProperty * property_value_height_offset_; - rviz_common::properties::FloatProperty * property_value_scale_; - rviz_common::properties::IntProperty * property_font_size_; - rviz_common::properties::IntProperty * property_max_letter_num_; - // QImage hud_; - -private: - static constexpr int line_width_ = 2; - static constexpr int hand_width_ = 4; - - std::mutex mutex_; - tier4_debug_msgs::msg::StringStamped::ConstSharedPtr last_msg_ptr_; -}; -} // namespace rviz_plugins - -#endif // TIER4_DEBUG_RVIZ_PLUGIN__STRING_STAMPED_HPP_ diff --git a/common/tier4_debug_rviz_plugin/package.xml b/common/tier4_debug_rviz_plugin/package.xml deleted file mode 100644 index 45b73d5b9815d..0000000000000 --- a/common/tier4_debug_rviz_plugin/package.xml +++ /dev/null @@ -1,30 +0,0 @@ - - - - tier4_debug_rviz_plugin - 0.1.0 - The tier4_debug_rviz_plugin package - Takayuki Murooka - Apache License 2.0 - - ament_cmake - autoware_cmake - - libqt5-core - libqt5-gui - libqt5-widgets - qtbase5-dev - rclcpp - rviz_common - rviz_default_plugins - rviz_rendering - tier4_debug_msgs - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - - diff --git a/common/tier4_debug_rviz_plugin/plugins/plugin_description.xml b/common/tier4_debug_rviz_plugin/plugins/plugin_description.xml deleted file mode 100644 index e18900afc8d84..0000000000000 --- a/common/tier4_debug_rviz_plugin/plugins/plugin_description.xml +++ /dev/null @@ -1,12 +0,0 @@ - - - Display drivable area of tier4_debug_msgs::msg::Float32MultiArrayStamped - - - Display drivable area of tier4_debug_msgs::msg::StringStamped - - diff --git a/common/tier4_debug_rviz_plugin/src/float32_multi_array_stamped_pie_chart.cpp b/common/tier4_debug_rviz_plugin/src/float32_multi_array_stamped_pie_chart.cpp deleted file mode 100644 index 0187cc3e22de0..0000000000000 --- a/common/tier4_debug_rviz_plugin/src/float32_multi_array_stamped_pie_chart.cpp +++ /dev/null @@ -1,479 +0,0 @@ -// 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. - -// Copyright (c) 2014, JSK Lab -// All rights reserved. -// -// Software License Agreement (BSD License) -// -// 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 {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 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.S SOFTWARE, EVEN IF ADVISED OF THE -// POSSIBILITY OF SUCH DAMAGE. - -#include -#include -#include -#include - -namespace rviz_plugins -{ - -Float32MultiArrayStampedPieChartDisplay::Float32MultiArrayStampedPieChartDisplay() -: rviz_common::Display(), update_required_(false), first_time_(true), data_(0.0) -{ - update_topic_property_ = new rviz_common::properties::StringProperty( - "Topic", "", "tier4_debug_msgs::msg::Float32MultiArrayStamped topic to subscribe to.", this, - SLOT(updateTopic()), this); - data_index_property_ = new rviz_common::properties::IntProperty( - "data index", 0, "data index in message to visualize", this, SLOT(updateDataIndex())); - size_property_ = new rviz_common::properties::IntProperty( - "size", 128, "size of the plotter window", this, SLOT(updateSize())); - left_property_ = new rviz_common::properties::IntProperty( - "left", 128, "left of the plotter window", this, SLOT(updateLeft())); - top_property_ = new rviz_common::properties::IntProperty( - "top", 128, "top of the plotter window", this, SLOT(updateTop())); - fg_color_property_ = new rviz_common::properties::ColorProperty( - "foreground color", QColor(25, 255, 240), "color to draw line", this, SLOT(updateFGColor())); - fg_alpha_property_ = new rviz_common::properties::FloatProperty( - "foreground alpha", 0.7, "alpha blending value for foreground", this, SLOT(updateFGAlpha())); - fg_alpha2_property_ = new rviz_common::properties::FloatProperty( - "foreground alpha 2", 0.4, "alpha blending value for foreground for indicator", this, - SLOT(updateFGAlpha2())); - 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.0, "alpha blending value for background", this, SLOT(updateBGAlpha())); - text_size_property_ = new rviz_common::properties::IntProperty( - "text size", 14, "text size", this, SLOT(updateTextSize())); - show_caption_property_ = new rviz_common::properties::BoolProperty( - "show caption", false, "show caption", this, SLOT(updateShowCaption())); - max_value_property_ = new rviz_common::properties::FloatProperty( - "max value", 1.0, "max value of pie chart", this, SLOT(updateMaxValue())); - min_value_property_ = new rviz_common::properties::FloatProperty( - "min value", 0.0, "min value of pie chart", this, SLOT(updateMinValue())); - auto_color_change_property_ = new rviz_common::properties::BoolProperty( - "auto color change", false, "change the color automatically", this, - SLOT(updateAutoColorChange())); - max_color_property_ = new rviz_common::properties::ColorProperty( - "max color", QColor(255, 0, 0), "only used if auto color change is set to True.", this, - SLOT(updateMaxColor())); - - med_color_property_ = new rviz_common::properties::ColorProperty( - "med color", QColor(255, 0, 0), "only used if auto color change is set to True.", this, - SLOT(updateMedColor())); - - max_color_threshold_property_ = new rviz_common::properties::FloatProperty( - "max color change threshold", 0, "change the max color at threshold", this, - SLOT(updateMaxColorThreshold())); - - med_color_threshold_property_ = new rviz_common::properties::FloatProperty( - "med color change threshold", 0, "change the med color at threshold ", this, - SLOT(updateMedColorThreshold())); - - clockwise_rotate_property_ = new rviz_common::properties::BoolProperty( - "clockwise rotate direction", false, "change the rotate direction", this, - SLOT(updateClockwiseRotate())); -} - -Float32MultiArrayStampedPieChartDisplay::~Float32MultiArrayStampedPieChartDisplay() -{ - if (overlay_->isVisible()) { - overlay_->hide(); - } - delete update_topic_property_; - delete fg_color_property_; - delete bg_color_property_; - delete fg_alpha_property_; - delete fg_alpha2_property_; - delete bg_alpha_property_; - delete top_property_; - delete left_property_; - delete size_property_; - delete min_value_property_; - delete max_value_property_; - delete max_color_property_; - delete med_color_property_; - delete text_size_property_; - delete show_caption_property_; -} - -void Float32MultiArrayStampedPieChartDisplay::onInitialize() -{ - static int count = 0; - rviz_common::UniformStringStream ss; - ss << "Float32MultiArrayStampedPieChart" << count++; - auto logger = context_->getRosNodeAbstraction().lock()->get_raw_node()->get_logger(); - overlay_.reset(new jsk_rviz_plugins::OverlayObject(scene_manager_, logger, ss.str())); - onEnable(); - updateSize(); - updateLeft(); - updateTop(); - updateFGColor(); - updateBGColor(); - updateFGAlpha(); - updateFGAlpha2(); - updateBGAlpha(); - updateMinValue(); - updateMaxValue(); - updateTextSize(); - updateShowCaption(); - updateAutoColorChange(); - updateMaxColor(); - updateMedColor(); - updateMaxColorThreshold(); - updateMedColorThreshold(); - updateClockwiseRotate(); - overlay_->updateTextureSize(texture_size_, texture_size_ + caption_offset_); - overlay_->hide(); -} - -void Float32MultiArrayStampedPieChartDisplay::update( - [[maybe_unused]] float wall_dt, [[maybe_unused]] float ros_dt) -{ - if (update_required_) { - update_required_ = false; - overlay_->updateTextureSize(texture_size_, texture_size_ + caption_offset_); - overlay_->setPosition(left_, top_); - overlay_->setDimensions(overlay_->getTextureWidth(), overlay_->getTextureHeight()); - drawPlot(data_); - } -} - -void Float32MultiArrayStampedPieChartDisplay::processMessage( - const tier4_debug_msgs::msg::Float32MultiArrayStamped::ConstSharedPtr msg) -{ - std::lock_guard lock(mutex_); - - if (!overlay_->isVisible()) { - return; - } - if (data_index_ < 0 || static_cast(msg->data.size()) <= data_index_) { - return; - } - - if (data_ != msg->data.at(data_index_) || first_time_) { - first_time_ = false; - data_ = msg->data.at(data_index_); - update_required_ = true; - } -} - -void Float32MultiArrayStampedPieChartDisplay::drawPlot(double val) -{ - QColor fg_color(fg_color_); - - if (auto_color_change_) { - double r = std::min(1.0, fabs((val - min_value_) / (max_value_ - min_value_))); - if (r > 0.6) { - double r2 = (r - 0.6) / 0.4; - fg_color.setRed((max_color_.red() - fg_color_.red()) * r2 + fg_color_.red()); - fg_color.setGreen((max_color_.green() - fg_color_.green()) * r2 + fg_color_.green()); - fg_color.setBlue((max_color_.blue() - fg_color_.blue()) * r2 + fg_color_.blue()); - } - if (max_color_threshold_ != 0) { - if (r > max_color_threshold_) { - fg_color.setRed(max_color_.red()); - fg_color.setGreen(max_color_.green()); - fg_color.setBlue(max_color_.blue()); - } - } - if (med_color_threshold_ != 0) { - if (max_color_threshold_ > r && r > med_color_threshold_) { - fg_color.setRed(med_color_.red()); - fg_color.setGreen(med_color_.green()); - fg_color.setBlue(med_color_.blue()); - } - } - } - - QColor fg_color2(fg_color); - QColor bg_color(bg_color_); - fg_color.setAlpha(fg_alpha_); - fg_color2.setAlpha(fg_alpha2_); - bg_color.setAlpha(bg_alpha_); - int width = overlay_->getTextureWidth(); - int height = overlay_->getTextureHeight(); - { - jsk_rviz_plugins::ScopedPixelBuffer buffer = overlay_->getBuffer(); - QImage Hud = buffer.getQImage(*overlay_, bg_color); - QPainter painter(&Hud); - painter.setRenderHint(QPainter::Antialiasing, true); - - const int outer_line_width = 5; - const int value_line_width = 10; - const int value_indicator_line_width = 2; - const int value_padding = 5; - - const int value_offset = outer_line_width + value_padding + value_line_width / 2; - - painter.setPen(QPen(fg_color, outer_line_width, Qt::SolidLine)); - - painter.drawEllipse( - outer_line_width / 2, outer_line_width / 2, width - outer_line_width, - height - outer_line_width - caption_offset_); - - painter.setPen(QPen(fg_color2, value_indicator_line_width, Qt::SolidLine)); - painter.drawEllipse( - value_offset, value_offset, width - value_offset * 2, - height - value_offset * 2 - caption_offset_); - - const double ratio = (val - min_value_) / (max_value_ - min_value_); - const double rotate_direction = clockwise_rotate_ ? -1.0 : 1.0; - const double ratio_angle = ratio * 360.0 * rotate_direction; - const double start_angle_offset = -90; - painter.setPen(QPen(fg_color, value_line_width, Qt::SolidLine)); - painter.drawArc( - QRectF( - value_offset, value_offset, width - value_offset * 2, - height - value_offset * 2 - caption_offset_), - start_angle_offset * 16, ratio_angle * 16); - QFont font = painter.font(); - font.setPointSize(text_size_); - font.setBold(true); - painter.setFont(font); - painter.setPen(QPen(fg_color, value_line_width, Qt::SolidLine)); - std::ostringstream s; - s << std::fixed << std::setprecision(2) << val; - painter.drawText( - 0, 0, width, height - caption_offset_, Qt::AlignCenter | Qt::AlignVCenter, s.str().c_str()); - - // caption - if (show_caption_) { - painter.drawText( - 0, height - caption_offset_, width, caption_offset_, Qt::AlignCenter | Qt::AlignVCenter, - getName()); - } - - // done - painter.end(); - // Unlock the pixel buffer - } -} - -void Float32MultiArrayStampedPieChartDisplay::subscribe() -{ - std::string topic_name = update_topic_property_->getStdString(); - - // NOTE: Remove all spaces since topic name filled with only spaces will crash - topic_name.erase(std::remove(topic_name.begin(), topic_name.end(), ' '), topic_name.end()); - - if (topic_name.length() > 0 && topic_name != "/") { - rclcpp::Node::SharedPtr raw_node = context_->getRosNodeAbstraction().lock()->get_raw_node(); - sub_ = raw_node->create_subscription( - topic_name, 1, - std::bind( - &Float32MultiArrayStampedPieChartDisplay::processMessage, this, std::placeholders::_1)); - } -} - -void Float32MultiArrayStampedPieChartDisplay::unsubscribe() -{ - sub_.reset(); -} - -void Float32MultiArrayStampedPieChartDisplay::onEnable() -{ - subscribe(); - overlay_->show(); - first_time_ = true; -} - -void Float32MultiArrayStampedPieChartDisplay::onDisable() -{ - unsubscribe(); - overlay_->hide(); -} - -void Float32MultiArrayStampedPieChartDisplay::updateSize() -{ - std::lock_guard lock(mutex_); - - texture_size_ = size_property_->getInt(); - update_required_ = true; -} - -void Float32MultiArrayStampedPieChartDisplay::updateTop() -{ - top_ = top_property_->getInt(); - update_required_ = true; -} - -void Float32MultiArrayStampedPieChartDisplay::updateLeft() -{ - left_ = left_property_->getInt(); - update_required_ = true; -} - -void Float32MultiArrayStampedPieChartDisplay::updateBGColor() -{ - bg_color_ = bg_color_property_->getColor(); - update_required_ = true; -} - -void Float32MultiArrayStampedPieChartDisplay::updateFGColor() -{ - fg_color_ = fg_color_property_->getColor(); - update_required_ = true; -} - -void Float32MultiArrayStampedPieChartDisplay::updateFGAlpha() -{ - fg_alpha_ = fg_alpha_property_->getFloat() * 255.0; - update_required_ = true; -} - -void Float32MultiArrayStampedPieChartDisplay::updateFGAlpha2() -{ - fg_alpha2_ = fg_alpha2_property_->getFloat() * 255.0; - update_required_ = true; -} - -void Float32MultiArrayStampedPieChartDisplay::updateBGAlpha() -{ - bg_alpha_ = bg_alpha_property_->getFloat() * 255.0; - update_required_ = true; -} - -void Float32MultiArrayStampedPieChartDisplay::updateMinValue() -{ - min_value_ = min_value_property_->getFloat(); - update_required_ = true; -} - -void Float32MultiArrayStampedPieChartDisplay::updateMaxValue() -{ - max_value_ = max_value_property_->getFloat(); - update_required_ = true; -} - -void Float32MultiArrayStampedPieChartDisplay::updateTextSize() -{ - std::lock_guard lock(mutex_); - - text_size_ = text_size_property_->getInt(); - QFont font; - font.setPointSize(text_size_); - caption_offset_ = QFontMetrics(font).height(); - update_required_ = true; -} - -void Float32MultiArrayStampedPieChartDisplay::updateShowCaption() -{ - show_caption_ = show_caption_property_->getBool(); - update_required_ = true; -} - -void Float32MultiArrayStampedPieChartDisplay::updateTopic() -{ - unsubscribe(); - subscribe(); -} - -void Float32MultiArrayStampedPieChartDisplay::updateDataIndex() -{ - data_index_ = data_index_property_->getInt(); - update_required_ = true; -} - -void Float32MultiArrayStampedPieChartDisplay::updateAutoColorChange() -{ - auto_color_change_ = auto_color_change_property_->getBool(); - if (auto_color_change_) { - max_color_property_->show(); - med_color_property_->show(); - max_color_threshold_property_->show(); - med_color_threshold_property_->show(); - } else { - max_color_property_->hide(); - med_color_property_->hide(); - max_color_threshold_property_->hide(); - med_color_threshold_property_->hide(); - } - update_required_ = true; -} - -void Float32MultiArrayStampedPieChartDisplay::updateMaxColor() -{ - max_color_ = max_color_property_->getColor(); - update_required_ = true; -} - -void Float32MultiArrayStampedPieChartDisplay::updateMedColor() -{ - med_color_ = med_color_property_->getColor(); - update_required_ = true; -} - -void Float32MultiArrayStampedPieChartDisplay::updateMaxColorThreshold() -{ - max_color_threshold_ = max_color_threshold_property_->getFloat(); - update_required_ = true; -} - -void Float32MultiArrayStampedPieChartDisplay::updateMedColorThreshold() -{ - med_color_threshold_ = med_color_threshold_property_->getFloat(); - update_required_ = true; -} - -void Float32MultiArrayStampedPieChartDisplay::updateClockwiseRotate() -{ - clockwise_rotate_ = clockwise_rotate_property_->getBool(); - update_required_ = true; -} - -bool Float32MultiArrayStampedPieChartDisplay::isInRegion(int x, int y) -{ - return (top_ < y && top_ + texture_size_ > y && left_ < x && left_ + texture_size_ > x); -} - -void Float32MultiArrayStampedPieChartDisplay::movePosition(int x, int y) -{ - top_ = y; - left_ = x; -} - -void Float32MultiArrayStampedPieChartDisplay::setPosition(int x, int y) -{ - top_property_->setValue(y); - left_property_->setValue(x); -} -} // namespace rviz_plugins - -#include -PLUGINLIB_EXPORT_CLASS(rviz_plugins::Float32MultiArrayStampedPieChartDisplay, rviz_common::Display) diff --git a/common/tier4_debug_rviz_plugin/src/jsk_overlay_utils.cpp b/common/tier4_debug_rviz_plugin/src/jsk_overlay_utils.cpp deleted file mode 100644 index b1933ebb3e157..0000000000000 --- a/common/tier4_debug_rviz_plugin/src/jsk_overlay_utils.cpp +++ /dev/null @@ -1,225 +0,0 @@ -// 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. - -// Copyright (c) 2014, JSK Lab -// All rights reserved. -// -// Software License Agreement (BSD License) -// -// 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 {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 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.S SOFTWARE, EVEN IF ADVISED OF THE -// POSSIBILITY OF SUCH DAMAGE. - -#include - -#include - -namespace jsk_rviz_plugins -{ -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( - Ogre::SceneManager * manager, rclcpp::Logger logger, const std::string & name) -: name_(name), logger_(logger) -{ - rviz_rendering::RenderSystem::get()->prepareOverlays(manager); - 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() -{ - hide(); - panel_material_->unload(); - Ogre::MaterialManager::getSingleton().remove(panel_material_->getName()); - // Ogre::OverlayManager* mOverlayMgr = Ogre::OverlayManager::getSingletonPtr(); - // mOverlayMgr->destroyOverlayElement(panel_); - // delete panel_; - // delete overlay_; -} - -std::string OverlayObject::getName() -{ - return name_; -} - -void OverlayObject::hide() -{ - if (overlay_->isVisible()) { - overlay_->hide(); - } -} - -void OverlayObject::show() -{ - if (!overlay_->isVisible()) { - overlay_->show(); - } -} - -bool OverlayObject::isTextureReady() -{ - return static_cast(texture_); -} - -void OverlayObject::updateTextureSize(unsigned int width, unsigned int height) -{ - const std::string texture_name = name_ + "Texture"; - if (width == 0) { - RCLCPP_WARN(logger_, "width=0 is specified as texture size"); - width = 1; - } - if (height == 0) { - RCLCPP_WARN(logger_, "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 left, double top) -{ - panel_->setPosition(left, top); -} - -void OverlayObject::setDimensions(double width, double height) -{ - panel_->setDimensions(width, height); -} - -bool OverlayObject::isVisible() -{ - return overlay_->isVisible(); -} - -unsigned int OverlayObject::getTextureWidth() -{ - if (isTextureReady()) { - return texture_->getWidth(); - } else { - return 0; - } -} - -unsigned int OverlayObject::getTextureHeight() -{ - if (isTextureReady()) { - return texture_->getHeight(); - } else { - return 0; - } -} - -} // namespace jsk_rviz_plugins diff --git a/common/tier4_debug_rviz_plugin/src/string_stamped.cpp b/common/tier4_debug_rviz_plugin/src/string_stamped.cpp deleted file mode 100644 index 538dc0cbe7069..0000000000000 --- a/common/tier4_debug_rviz_plugin/src/string_stamped.cpp +++ /dev/null @@ -1,198 +0,0 @@ -// 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. - -// Copyright (c) 2014, JSK Lab -// All rights reserved. -// -// Software License Agreement (BSD License) -// -// 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 {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 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.S SOFTWARE, EVEN IF ADVISED OF THE -// POSSIBILITY OF SUCH DAMAGE. - -#include "tier4_debug_rviz_plugin/string_stamped.hpp" - -#include "tier4_debug_rviz_plugin/jsk_overlay_utils.hpp" - -#include -#include - -#include - -#include -#include -#include -#include - -namespace rviz_plugins -{ -StringStampedOverlayDisplay::StringStampedOverlayDisplay() -{ - const Screen * screen_info = DefaultScreenOfDisplay(XOpenDisplay(NULL)); - - constexpr float hight_4k = 2160.0; - const float scale = static_cast(screen_info->height) / hight_4k; - const auto left = static_cast(std::round(1024 * scale)); - const auto top = static_cast(std::round(128 * scale)); - - property_text_color_ = new rviz_common::properties::ColorProperty( - "Text Color", QColor(25, 255, 240), "text color", this, SLOT(updateVisualization()), this); - property_left_ = new rviz_common::properties::IntProperty( - "Left", left, "Left of the plotter window", this, SLOT(updateVisualization()), this); - property_left_->setMin(0); - property_top_ = new rviz_common::properties::IntProperty( - "Top", top, "Top of the plotter window", this, SLOT(updateVisualization())); - property_top_->setMin(0); - - property_value_height_offset_ = new rviz_common::properties::IntProperty( - "Value height offset", 0, "Height offset of the plotter window", this, - SLOT(updateVisualization())); - property_font_size_ = new rviz_common::properties::IntProperty( - "Font Size", 15, "Font Size", this, SLOT(updateVisualization()), this); - property_font_size_->setMin(1); - property_max_letter_num_ = new rviz_common::properties::IntProperty( - "Max Letter Num", 100, "Max Letter Num", this, SLOT(updateVisualization()), this); - property_max_letter_num_->setMin(10); -} - -StringStampedOverlayDisplay::~StringStampedOverlayDisplay() -{ - if (initialized()) { - overlay_->hide(); - } -} - -void StringStampedOverlayDisplay::onInitialize() -{ - RTDClass::onInitialize(); - - static int count = 0; - rviz_common::UniformStringStream ss; - ss << "StringOverlayDisplayObject" << count++; - auto logger = context_->getRosNodeAbstraction().lock()->get_raw_node()->get_logger(); - overlay_.reset(new jsk_rviz_plugins::OverlayObject(scene_manager_, logger, ss.str())); - - overlay_->show(); - - const int texture_size = property_font_size_->getInt() * property_max_letter_num_->getInt(); - overlay_->updateTextureSize(texture_size, texture_size); - overlay_->setPosition(property_left_->getInt(), property_top_->getInt()); - overlay_->setDimensions(overlay_->getTextureWidth(), overlay_->getTextureHeight()); -} - -void StringStampedOverlayDisplay::onEnable() -{ - subscribe(); - overlay_->show(); -} - -void StringStampedOverlayDisplay::onDisable() -{ - unsubscribe(); - reset(); - overlay_->hide(); -} - -void StringStampedOverlayDisplay::update(float wall_dt, float ros_dt) -{ - (void)wall_dt; - (void)ros_dt; - - std::lock_guard message_lock(mutex_); - if (!last_msg_ptr_) { - return; - } - - // Display - QColor background_color; - background_color.setAlpha(0); - jsk_rviz_plugins::ScopedPixelBuffer buffer = overlay_->getBuffer(); - QImage hud = buffer.getQImage(*overlay_); - hud.fill(background_color); - - QPainter painter(&hud); - painter.setRenderHint(QPainter::Antialiasing, true); - - const int w = overlay_->getTextureWidth() - line_width_; - const int h = overlay_->getTextureHeight() - line_width_; - - // text - QColor text_color(property_text_color_->getColor()); - text_color.setAlpha(255); - painter.setPen(QPen(text_color, static_cast(2), Qt::SolidLine)); - QFont font = painter.font(); - font.setPixelSize(property_font_size_->getInt()); - font.setBold(true); - painter.setFont(font); - - // same as above, but align on right side - painter.drawText( - 0, std::min(property_value_height_offset_->getInt(), h - 1), w, - std::max(h - property_value_height_offset_->getInt(), 1), Qt::AlignLeft | Qt::AlignTop, - last_msg_ptr_->data.c_str()); - painter.end(); - updateVisualization(); -} - -void StringStampedOverlayDisplay::processMessage( - const tier4_debug_msgs::msg::StringStamped::ConstSharedPtr msg_ptr) -{ - if (!isEnabled()) { - return; - } - - { - std::lock_guard message_lock(mutex_); - last_msg_ptr_ = msg_ptr; - } - - queueRender(); -} - -void StringStampedOverlayDisplay::updateVisualization() -{ - const int texture_size = property_font_size_->getInt() * property_max_letter_num_->getInt(); - overlay_->updateTextureSize(texture_size, texture_size); - overlay_->setPosition(property_left_->getInt(), property_top_->getInt()); - overlay_->setDimensions(overlay_->getTextureWidth(), overlay_->getTextureHeight()); -} - -} // namespace rviz_plugins - -#include -PLUGINLIB_EXPORT_CLASS(rviz_plugins::StringStampedOverlayDisplay, rviz_common::Display) diff --git a/common/tier4_logging_level_configure_rviz_plugin/CMakeLists.txt b/common/tier4_logging_level_configure_rviz_plugin/CMakeLists.txt deleted file mode 100644 index cc7da7e322d19..0000000000000 --- a/common/tier4_logging_level_configure_rviz_plugin/CMakeLists.txt +++ /dev/null @@ -1,28 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(tier4_logging_level_configure_rviz_plugin) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -find_package(Qt5 REQUIRED Core Widgets) -set(QT_LIBRARIES Qt5::Widgets) -set(CMAKE_AUTOMOC ON) -add_definitions(-DQT_NO_KEYWORDS) - -ament_auto_add_library(tier4_logging_level_configure_rviz_plugin SHARED - include/tier4_logging_level_configure_rviz_plugin/logging_level_configure.hpp - src/logging_level_configure.cpp -) - -target_link_libraries(tier4_logging_level_configure_rviz_plugin - ${QT_LIBRARIES} -) - -# 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 - plugins - config -) diff --git a/common/tier4_logging_level_configure_rviz_plugin/README.md b/common/tier4_logging_level_configure_rviz_plugin/README.md deleted file mode 100644 index ed400e521e6aa..0000000000000 --- a/common/tier4_logging_level_configure_rviz_plugin/README.md +++ /dev/null @@ -1,72 +0,0 @@ -# tier4_logging_level_configure_rviz_plugin - -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. - -!!! 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`. 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 deleted file mode 100644 index edea0ec5f17d3..0000000000000 --- a/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml +++ /dev/null @@ -1,126 +0,0 @@ -# logger_config.yaml - -# ============================================================ -# localization -# ============================================================ -Localization: - ndt_scan_matcher: - - node_name: /localization/pose_estimator/ndt_scan_matcher - logger_name: localization.pose_estimator.ndt_scan_matcher - - gyro_odometer: - - node_name: /localization/twist_estimator/gyro_odometer - logger_name: localization.twist_estimator.gyro_odometer - - pose_initializer: - - node_name: /localization/util/pose_initializer_node - logger_name: localization.util.pose_initializer_node - - ekf_localizer: - - node_name: /localization/pose_twist_fusion_filter/ekf_localizer - logger_name: localization.pose_twist_fusion_filter.ekf_localizer - - localization_error_monitor: - - node_name: /localization/localization_error_monitor - logger_name: localization.localization_error_monitor - -# ============================================================ -# planning -# ============================================================ -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 - 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/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 - logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.goal_planner - - behavior_path_planner_start_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.start_planner - - behavior_path_avoidance_by_lane_change: - - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner - logger_name: lane_change.AVOIDANCE_BY_LANE_CHANGE - - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner - logger_name: lane_change.utils - - behavior_path_lane_change: - - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner - logger_name: lane_change.NORMAL - - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner - logger_name: lane_change.utils - - 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 - logger_name: tier4_autoware_utils - - behavior_velocity_planner_intersection: - - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner - logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_velocity_planner.intersection - - 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 - 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 - logger_name: tier4_autoware_utils - -# ============================================================ -# control -# ============================================================ -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 - 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 - 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 - logger_name: tier4_autoware_utils - -# ============================================================ -# common -# ============================================================ - -Common: - tier4_autoware_utils: - - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner - logger_name: tier4_autoware_utils - - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner - 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 - logger_name: tier4_autoware_utils diff --git a/common/tier4_logging_level_configure_rviz_plugin/include/tier4_logging_level_configure_rviz_plugin/logging_level_configure.hpp b/common/tier4_logging_level_configure_rviz_plugin/include/tier4_logging_level_configure_rviz_plugin/logging_level_configure.hpp deleted file mode 100644 index 37d70b494c74e..0000000000000 --- a/common/tier4_logging_level_configure_rviz_plugin/include/tier4_logging_level_configure_rviz_plugin/logging_level_configure.hpp +++ /dev/null @@ -1,90 +0,0 @@ -// 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 TIER4_LOGGING_LEVEL_CONFIGURE_RVIZ_PLUGIN__LOGGING_LEVEL_CONFIGURE_HPP_ -#define TIER4_LOGGING_LEVEL_CONFIGURE_RVIZ_PLUGIN__LOGGING_LEVEL_CONFIGURE_HPP_ - -#include "logging_demo/srv/config_logger.hpp" - -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include - -namespace rviz_plugin -{ -struct LoggerInfo -{ - QString node_name; - QString logger_name; -}; -struct ButtonInfo -{ - QString button_name; - std::vector logger_info_vec; -}; -struct LoggerNamespaceInfo -{ - QString ns; // group namespace - std::vector button_info_vec; -}; -class LoggingLevelConfigureRvizPlugin : public rviz_common::Panel -{ - Q_OBJECT // This macro is needed for Qt to handle slots and signals - - public : LoggingLevelConfigureRvizPlugin(QWidget * parent = nullptr); - void onInitialize() override; - void save(rviz_common::Config config) const override; - void load(const rviz_common::Config & config) override; - -private: - QMap buttonGroups_; - rclcpp::Node::SharedPtr raw_node_; - - std::vector display_info_vec_; - - // client_map_[node_name] = service_client - std::unordered_map::SharedPtr> - client_map_; - - // button_map_[button_name][logging_level] = Q_button_pointer - std::unordered_map> button_map_; - - QStringList getNodeList(); - int getMaxModuleNameWidth(QLabel * containerLabel); - void setLoggerNodeMap(); - - ButtonInfo getButtonInfoFromNamespace(const QString & ns); - std::vector getNodeLoggerNameFromButtonName(const QString button_name); - -private Q_SLOTS: - void onButtonClick(QPushButton * button, const QString & name, const QString & level); - void updateButtonColors( - const QString & target_module_name, QPushButton * active_button, const QString & level); - void changeLogLevel(const QString & container, const QString & level); -}; - -} // namespace rviz_plugin - -#endif // TIER4_LOGGING_LEVEL_CONFIGURE_RVIZ_PLUGIN__LOGGING_LEVEL_CONFIGURE_HPP_ diff --git a/common/tier4_logging_level_configure_rviz_plugin/package.xml b/common/tier4_logging_level_configure_rviz_plugin/package.xml deleted file mode 100644 index 7849e6049a077..0000000000000 --- a/common/tier4_logging_level_configure_rviz_plugin/package.xml +++ /dev/null @@ -1,33 +0,0 @@ - - - - tier4_logging_level_configure_rviz_plugin - 0.1.0 - The tier4_logging_level_configure_rviz_plugin package - Takamasa Horibe - Satoshi Ota - Kosuke Takeuchi - Apache License 2.0 - - ament_cmake - autoware_cmake - - libqt5-core - libqt5-gui - libqt5-widgets - logging_demo - qtbase5-dev - rclcpp - rviz_common - rviz_default_plugins - rviz_rendering - yaml-cpp - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - - diff --git a/common/tier4_logging_level_configure_rviz_plugin/plugins/plugin_description.xml b/common/tier4_logging_level_configure_rviz_plugin/plugins/plugin_description.xml deleted file mode 100644 index ce5cbd13fc131..0000000000000 --- a/common/tier4_logging_level_configure_rviz_plugin/plugins/plugin_description.xml +++ /dev/null @@ -1,7 +0,0 @@ - - - tier4_logging_level_configure_rviz_plugin - - diff --git a/common/tier4_logging_level_configure_rviz_plugin/src/logging_level_configure.cpp b/common/tier4_logging_level_configure_rviz_plugin/src/logging_level_configure.cpp deleted file mode 100644 index 72ecf361c96d5..0000000000000 --- a/common/tier4_logging_level_configure_rviz_plugin/src/logging_level_configure.cpp +++ /dev/null @@ -1,258 +0,0 @@ -// 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. - -#include "yaml-cpp/yaml.h" - -#include -#include -#include -#include -#include -#include - -#include - -namespace rviz_plugin -{ - -LoggingLevelConfigureRvizPlugin::LoggingLevelConfigureRvizPlugin(QWidget * parent) -: rviz_common::Panel(parent) -{ -} - -void LoggingLevelConfigureRvizPlugin::onInitialize() -{ - raw_node_ = this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); - - setLoggerNodeMap(); - - QVBoxLayout * mainLayout = new QVBoxLayout; - - QStringList levels = {"DEBUG", "INFO", "WARN", "ERROR", "FATAL"}; - - constexpr int height = 20; - - // Iterate over the namespaces - for (const auto & ns_group_info : display_info_vec_) { - // Create a group box for each namespace - QGroupBox * groupBox = new QGroupBox(ns_group_info.ns); - QVBoxLayout * groupLayout = new QVBoxLayout; - - // Iterate over the node/logger pairs within this namespace - for (const auto & button_info : ns_group_info.button_info_vec) { - const auto & button_name = button_info.button_name; - - QHBoxLayout * hLayout = new QHBoxLayout; - - // Create a QLabel to display the node name - QLabel * label = new QLabel(button_name); - label->setFixedHeight(height); - label->setFixedWidth(getMaxModuleNameWidth(label)); - - hLayout->addWidget(label); - - // Create a button group for each node - QButtonGroup * buttonGroup = new QButtonGroup(this); - - // Create buttons for each logging level - for (const QString & level : levels) { - QPushButton * button = new QPushButton(level); - button->setFixedHeight(height); - hLayout->addWidget(button); - buttonGroup->addButton(button); - button_map_[button_name][level] = button; - connect(button, &QPushButton::clicked, this, [this, button, button_name, level]() { - this->onButtonClick(button, button_name, level); - }); - } - - // Set the "INFO" button as checked by default and change its color - updateButtonColors(button_name, button_map_[button_name]["INFO"], "INFO"); - - buttonGroups_[button_name] = buttonGroup; - groupLayout->addLayout(hLayout); // Add the horizontal layout to the group layout - } - - groupBox->setLayout(groupLayout); // Set the group layout to the group box - mainLayout->addWidget(groupBox); // Add the group box to the main layout - } - - // Create a QWidget to hold the main layout - QWidget * containerWidget = new QWidget; - containerWidget->setLayout(mainLayout); - - // Create a QScrollArea to make the layout scrollable - QScrollArea * scrollArea = new QScrollArea; - scrollArea->setWidget(containerWidget); - scrollArea->setWidgetResizable(true); - - // Set the QScrollArea as the layout of the main widget - QVBoxLayout * scrollLayout = new QVBoxLayout; - scrollLayout->addWidget(scrollArea); - setLayout(scrollLayout); - - // Setup service clients - const auto & nodes = getNodeList(); - for (const QString & node : nodes) { - const auto client = raw_node_->create_client( - node.toStdString() + "/config_logger"); - client_map_[node] = client; - } -} - -// Calculate the maximum width among all target_module_name. -int LoggingLevelConfigureRvizPlugin::getMaxModuleNameWidth(QLabel * label) -{ - int max_width = 0; - QFontMetrics metrics(label->font()); - for (const auto & ns_info : display_info_vec_) { - for (const auto & b : ns_info.button_info_vec) { - max_width = std::max(metrics.horizontalAdvance(b.button_name), max_width); - } - } - return max_width; -} - -// create node list in node_logger_map_ without -QStringList LoggingLevelConfigureRvizPlugin::getNodeList() -{ - QStringList nodes; - for (const auto & d : display_info_vec_) { - for (const auto & b : d.button_info_vec) { - for (const auto & info : b.logger_info_vec) { - if (!nodes.contains(info.node_name)) { - nodes.append(info.node_name); - } - } - } - } - return nodes; -} - -// Modify the signature of the onButtonClick function: -void LoggingLevelConfigureRvizPlugin::onButtonClick( - QPushButton * button, const QString & target_module_name, const QString & level) -{ - if (button) { - const auto callback = - [&](rclcpp::Client::SharedFuture future) { - std::cerr << "change logging level: " - << std::string(future.get()->success ? "success!" : "failed...") << std::endl; - }; - - const auto node_logger_vec = getNodeLoggerNameFromButtonName(target_module_name); - for (const auto & data : node_logger_vec) { - const auto req = std::make_shared(); - - req->logger_name = data.logger_name.toStdString(); - req->level = level.toStdString(); - std::cerr << "logger level of " << req->logger_name << " is set to " << req->level - << std::endl; - client_map_[data.node_name]->async_send_request(req, callback); - } - - updateButtonColors( - target_module_name, button, level); // Modify updateButtonColors to accept QPushButton only. - } -} - -void LoggingLevelConfigureRvizPlugin::updateButtonColors( - const QString & target_module_name, QPushButton * active_button, const QString & level) -{ - std::unordered_map colorMap = { - {"DEBUG", "rgb(181, 255, 20)"}, /* green */ - {"INFO", "rgb(200, 255, 255)"}, /* light blue */ - {"WARN", "rgb(255, 255, 0)"}, /* yellow */ - {"ERROR", "rgb(255, 0, 0)"}, /* red */ - {"FATAL", "rgb(139, 0, 0)"}, /* dark red */ - {"OFF", "rgb(211, 211, 211)"} /* gray */ - }; - - const QString LIGHT_GRAY_TEXT = "rgb(180, 180, 180)"; - - const QString color = colorMap.count(level) ? colorMap[level] : colorMap["OFF"]; - - for (const auto & button : button_map_[target_module_name]) { - if (button.second == active_button) { - button.second->setStyleSheet("background-color: " + color + "; color: black"); - } else { - button.second->setStyleSheet( - "background-color: " + colorMap["OFF"] + "; color: " + LIGHT_GRAY_TEXT); - } - } -} -void LoggingLevelConfigureRvizPlugin::save(rviz_common::Config config) const -{ - Panel::save(config); -} - -void LoggingLevelConfigureRvizPlugin::load(const rviz_common::Config & config) -{ - Panel::load(config); -} - -void LoggingLevelConfigureRvizPlugin::setLoggerNodeMap() -{ - const std::string package_share_directory = - ament_index_cpp::get_package_share_directory("tier4_logging_level_configure_rviz_plugin"); - const std::string default_config_path = package_share_directory + "/config/logger_config.yaml"; - - const auto filename = - raw_node_->declare_parameter("config_filename", default_config_path); - RCLCPP_INFO(raw_node_->get_logger(), "load config file: %s", filename.c_str()); - - YAML::Node config = YAML::LoadFile(filename); - - for (YAML::const_iterator it = config.begin(); it != config.end(); ++it) { - const auto ns = QString::fromStdString(it->first.as()); - const YAML::Node ns_config = it->second; - - LoggerNamespaceInfo display_data; - display_data.ns = ns; - - for (YAML::const_iterator ns_it = ns_config.begin(); ns_it != ns_config.end(); ++ns_it) { - const auto key = QString::fromStdString(ns_it->first.as()); - ButtonInfo button_data; - button_data.button_name = key; - const YAML::Node values = ns_it->second; - for (size_t i = 0; i < values.size(); i++) { - LoggerInfo data; - data.node_name = QString::fromStdString(values[i]["node_name"].as()); - data.logger_name = QString::fromStdString(values[i]["logger_name"].as()); - button_data.logger_info_vec.push_back(data); - } - display_data.button_info_vec.push_back(button_data); - } - display_info_vec_.push_back(display_data); - } -} - -std::vector LoggingLevelConfigureRvizPlugin::getNodeLoggerNameFromButtonName( - const QString button_name) -{ - for (const auto & ns_level : display_info_vec_) { - for (const auto & button : ns_level.button_info_vec) { - if (button.button_name == button_name) { - return button.logger_info_vec; - } - } - } - RCLCPP_ERROR( - raw_node_->get_logger(), "Failed to find target name: %s", button_name.toStdString().c_str()); - return {}; -} - -} // namespace rviz_plugin -#include -PLUGINLIB_EXPORT_CLASS(rviz_plugin::LoggingLevelConfigureRvizPlugin, rviz_common::Panel) diff --git a/common/tier4_logging_level_configure_rviz_plugin/tier4_logging_level_configure_rviz_plugin.png b/common/tier4_logging_level_configure_rviz_plugin/tier4_logging_level_configure_rviz_plugin.png deleted file mode 100644 index a93aff724bb19..0000000000000 Binary files a/common/tier4_logging_level_configure_rviz_plugin/tier4_logging_level_configure_rviz_plugin.png and /dev/null differ diff --git a/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp b/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp index 4a59006e3bb96..c915e38977012 100644 --- a/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp +++ b/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp @@ -316,6 +316,9 @@ class AutowarePathBaseDisplay : public rviz_common::MessageFilterDisplay node->detachAllObjects(); node->removeAndDestroyAllChildren(); this->scene_manager_->destroySceneNode(node); + + rviz_rendering::MovableText * text = velocity_texts_.at(i); + delete text; } velocity_texts_.resize(msg_ptr->points.size()); velocity_text_nodes_.resize(msg_ptr->points.size()); @@ -339,6 +342,9 @@ class AutowarePathBaseDisplay : public rviz_common::MessageFilterDisplay node->detachAllObjects(); node->removeAndDestroyAllChildren(); this->scene_manager_->destroySceneNode(node); + + rviz_rendering::MovableText * text = slope_texts_.at(i); + delete text; } slope_texts_.resize(msg_ptr->points.size()); slope_text_nodes_.resize(msg_ptr->points.size()); diff --git a/common/tier4_screen_capture_rviz_plugin/CMakeLists.txt b/common/tier4_screen_capture_rviz_plugin/CMakeLists.txt deleted file mode 100644 index 5b6e205bafed5..0000000000000 --- a/common/tier4_screen_capture_rviz_plugin/CMakeLists.txt +++ /dev/null @@ -1,29 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(tier4_screen_capture_rviz_plugin) - -find_package(autoware_cmake REQUIRED) -autoware_package() -find_package(OpenCV REQUIRED) -find_package(Qt5 REQUIRED Core Widgets) -set(QT_LIBRARIES Qt5::Widgets) -set(CMAKE_AUTOMOC ON) -set(CMAKE_INCLUDE_CURRENT_DIR ON) - -include_directories( - ${OpenCV_INCLUDE_DIRS} -) - -ament_auto_add_library(${PROJECT_NAME} SHARED - src/screen_capture_panel.hpp - src/screen_capture_panel.cpp -) -target_link_libraries(${PROJECT_NAME} - ${QT_LIBRARIES} - ${OpenCV_LIBRARIES} -) -pluginlib_export_plugin_description_file(rviz_common plugins/plugin_description.xml) - -ament_auto_package( - INSTALL_TO_SHARE - plugins -) diff --git a/common/tier4_screen_capture_rviz_plugin/README.md b/common/tier4_screen_capture_rviz_plugin/README.md deleted file mode 100644 index d16c19c343017..0000000000000 --- a/common/tier4_screen_capture_rviz_plugin/README.md +++ /dev/null @@ -1,23 +0,0 @@ -# tier4_screen_capture_rviz_plugin - -## Purpose - -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. -The `capture screen` button is still beta version which can slow frame rate. -set lower frame rate according to PC spec. - -## Usage - -1. Start rviz and select panels/Add new panel. - ![select_panel](./images/select_panels.png) diff --git a/common/tier4_screen_capture_rviz_plugin/images/select_panels.png b/common/tier4_screen_capture_rviz_plugin/images/select_panels.png deleted file mode 100644 index a691602c42c3c..0000000000000 Binary files a/common/tier4_screen_capture_rviz_plugin/images/select_panels.png and /dev/null differ diff --git a/common/tier4_screen_capture_rviz_plugin/package.xml b/common/tier4_screen_capture_rviz_plugin/package.xml deleted file mode 100644 index 180bf9eedc9ca..0000000000000 --- a/common/tier4_screen_capture_rviz_plugin/package.xml +++ /dev/null @@ -1,31 +0,0 @@ - - - - tier4_screen_capture_rviz_plugin - 0.0.0 - The screen capture package - Taiki, Tanaka - Satoshi Ota - Kyoichi Sugahara - Apache License 2.0 - - ament_cmake_auto - autoware_cmake - - libopencv-dev - libqt5-core - libqt5-gui - libqt5-widgets - qtbase5-dev - rclcpp - rviz_common - rviz_rendering - std_srvs - ament_lint_auto - autoware_lint_common - - - ament_cmake - - - diff --git a/common/tier4_screen_capture_rviz_plugin/plugins/plugin_description.xml b/common/tier4_screen_capture_rviz_plugin/plugins/plugin_description.xml deleted file mode 100644 index fdf105d646497..0000000000000 --- a/common/tier4_screen_capture_rviz_plugin/plugins/plugin_description.xml +++ /dev/null @@ -1,9 +0,0 @@ - - - - AutowareScreenCapturePanel - - - 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 deleted file mode 100644 index cad828903e0d3..0000000000000 --- a/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.cpp +++ /dev/null @@ -1,220 +0,0 @@ -// Copyright 2021 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 "screen_capture_panel.hpp" - -#include - -#include -#include -#include - -using std::placeholders::_1; -using std::placeholders::_2; - -void setFormatDate(QLabel * line, double time) -{ - char buffer[128]; - auto seconds = static_cast(time); - strftime(buffer, sizeof(buffer), "%Y-%m-%d-%H-%M-%S", localtime(&seconds)); - line->setText(QString("- ") + QString(buffer)); -} - -AutowareScreenCapturePanel::AutowareScreenCapturePanel(QWidget * parent) -: rviz_common::Panel(parent) -{ - std::filesystem::create_directory("capture"); - auto * v_layout = new QVBoxLayout; - // screen capture - auto * cap_layout = new QHBoxLayout; - { - ros_time_label_ = new QLabel; - screen_capture_button_ptr_ = new QPushButton("Capture Screen Shot"); - connect(screen_capture_button_ptr_, SIGNAL(clicked()), this, SLOT(onClickScreenCapture())); - file_name_prefix_ = new QLineEdit("cap"); - connect(file_name_prefix_, SIGNAL(valueChanged(std::string)), this, SLOT(onPrefixChanged())); - cap_layout->addWidget(screen_capture_button_ptr_); - cap_layout->addWidget(file_name_prefix_); - cap_layout->addWidget(ros_time_label_); - // initialize file name system clock is better for identification. - setFormatDate(ros_time_label_, rclcpp::Clock().now().seconds()); - } - - // video capture - auto * video_cap_layout = new QHBoxLayout; - { - capture_to_mp4_button_ptr_ = new QPushButton("Capture Screen"); - connect(capture_to_mp4_button_ptr_, SIGNAL(clicked()), this, SLOT(onClickVideoCapture())); - capture_hz_ = new QSpinBox(); - capture_hz_->setRange(1, 10); - capture_hz_->setValue(10); - capture_hz_->setSingleStep(1); - connect(capture_hz_, SIGNAL(valueChanged(int)), this, SLOT(onRateChanged())); - // video cap layout - video_cap_layout->addWidget(capture_to_mp4_button_ptr_); - video_cap_layout->addWidget(capture_hz_); - video_cap_layout->addWidget(new QLabel(" [Hz]")); - } - - // consider layout - { - v_layout->addLayout(cap_layout); - v_layout->addLayout(video_cap_layout); - setLayout(v_layout); - } - auto * timer = new QTimer(this); - connect(timer, &QTimer::timeout, this, &AutowareScreenCapturePanel::update); - timer->start(1000); - capture_timer_ = new QTimer(this); - connect(capture_timer_, &QTimer::timeout, this, &AutowareScreenCapturePanel::onTimer); - state_ = State::WAITING_FOR_CAPTURE; -} - -void AutowareScreenCapturePanel::onCaptureVideoTrigger( - [[maybe_unused]] const std_srvs::srv::Trigger::Request::SharedPtr req, - const std_srvs::srv::Trigger::Response::SharedPtr res) -{ - onClickVideoCapture(); - res->success = true; - 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_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() -{ -} - -void AutowareScreenCapturePanel::onRateChanged() -{ -} - -void AutowareScreenCapturePanel::onClickScreenCapture() -{ - const std::string time_text = - "capture/" + file_name_prefix_->text().toStdString() + ros_time_label_->text().toStdString(); - getDisplayContext()->getViewManager()->getRenderPanel()->getRenderWindow()->captureScreenShot( - time_text + ".png"); -} - -void AutowareScreenCapturePanel::onClickVideoCapture() -{ - const int clock = static_cast(1e3 / capture_hz_->value()); - try { - const QWidgetList top_level_widgets = QApplication::topLevelWidgets(); - for (QWidget * widget : top_level_widgets) { - auto * main_window_candidate = qobject_cast(widget); - if (main_window_candidate) { - main_window_ = main_window_candidate; - } - } - } catch (...) { - return; - } - if (!main_window_) return; - switch (state_) { - case State::WAITING_FOR_CAPTURE: - // initialize setting - { - capture_file_name_ = ros_time_label_->text().toStdString(); - } - capture_to_mp4_button_ptr_->setText("capturing rviz screen"); - capture_to_mp4_button_ptr_->setStyleSheet("background-color: #FF0000;"); - { - int fourcc = cv::VideoWriter::fourcc('h', '2', '6', '4'); // mp4 - QScreen * screen = QGuiApplication::primaryScreen(); - const auto q_size = screen->grabWindow(main_window_->winId()) - .toImage() - .convertToFormat(QImage::Format_RGB888) - .rgbSwapped() - .size(); - current_movie_size_ = cv::Size(q_size.width(), q_size.height()); - writer_.open( - "capture/" + file_name_prefix_->text().toStdString() + capture_file_name_ + ".mp4", - fourcc, capture_hz_->value(), current_movie_size_); - } - capture_timer_->start(clock); - state_ = State::CAPTURING; - break; - case State::CAPTURING: - writer_.release(); - capture_timer_->stop(); - capture_to_mp4_button_ptr_->setText("waiting for capture"); - capture_to_mp4_button_ptr_->setStyleSheet("background-color: #00FF00;"); - state_ = State::WAITING_FOR_CAPTURE; - break; - } -} - -void AutowareScreenCapturePanel::onTimer() -{ - if (!main_window_) return; - // this is deprecated but only way to capture nicely - QScreen * screen = QGuiApplication::primaryScreen(); - QPixmap original_pixmap = screen->grabWindow(main_window_->winId()); - const auto q_image = - original_pixmap.toImage().convertToFormat(QImage::Format_RGB888).rgbSwapped(); - const int h = q_image.height(); - const int w = q_image.width(); - cv::Size size = cv::Size(w, h); - cv::Mat image( - size, CV_8UC3, const_cast(q_image.bits()), - static_cast(q_image.bytesPerLine())); - if (size != current_movie_size_) { - cv::Mat new_image; - cv::resize(image, new_image, current_movie_size_); - writer_.write(new_image); - } else { - writer_.write(image); - } - cv::waitKey(0); -} - -void AutowareScreenCapturePanel::update() -{ - setFormatDate(ros_time_label_, rclcpp::Clock().now().seconds()); -} - -void AutowareScreenCapturePanel::save(rviz_common::Config config) const -{ - Panel::save(config); -} - -void AutowareScreenCapturePanel::load(const rviz_common::Config & config) -{ - Panel::load(config); -} - -AutowareScreenCapturePanel::~AutowareScreenCapturePanel() = default; - -#include -PLUGINLIB_EXPORT_CLASS(AutowareScreenCapturePanel, rviz_common::Panel) 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 deleted file mode 100644 index 5c4d16f57da82..0000000000000 --- a/common/tier4_screen_capture_rviz_plugin/src/screen_capture_panel.hpp +++ /dev/null @@ -1,109 +0,0 @@ -// Copyright 2021 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 SCREEN_CAPTURE_PANEL_HPP_ -#define SCREEN_CAPTURE_PANEL_HPP_ - -// Qt -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -// rviz -#include -#include -#include -#include -#include -#include -#include - -// ros -#include - -#include -#include -#include - -class QLineEdit; - -class AutowareScreenCapturePanel : public rviz_common::Panel -{ - Q_OBJECT - -public: - explicit AutowareScreenCapturePanel(QWidget * parent = nullptr); - ~AutowareScreenCapturePanel() override; - void update(); - void onInitialize() override; - void createWallTimer(); - void onTimer(); - void save(rviz_common::Config config) const override; - void load(const rviz_common::Config & config) override; - 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); - -public Q_SLOTS: - void onClickScreenCapture(); - void onClickVideoCapture(); - void onPrefixChanged(); - void onRateChanged(); - -private: - QLabel * ros_time_label_; - QPushButton * screen_capture_button_ptr_; - QPushButton * capture_to_mp4_button_ptr_; - QLineEdit * file_name_prefix_; - QSpinBox * capture_hz_; - QTimer * capture_timer_; - QMainWindow * main_window_{nullptr}; - enum class State { WAITING_FOR_CAPTURE, CAPTURING }; - State state_; - std::string capture_file_name_; - bool is_capture_{false}; - cv::VideoWriter writer_; - cv::Size current_movie_size_; - std::vector image_vec_; - - static std::string stateToString(const State & state) - { - if (state == State::WAITING_FOR_CAPTURE) { - return "waiting for capture"; - } - if (state == State::CAPTURING) { - return "capturing"; - } - return ""; - } - -protected: - rclcpp::Service::SharedPtr capture_video_srv_; - rclcpp::Service::SharedPtr capture_screen_shot_srv_; - rclcpp::Node::SharedPtr raw_node_; -}; - -#endif // SCREEN_CAPTURE_PANEL_HPP_ diff --git a/common/tier4_simulated_clock_rviz_plugin/CMakeLists.txt b/common/tier4_simulated_clock_rviz_plugin/CMakeLists.txt deleted file mode 100644 index 020766340016e..0000000000000 --- a/common/tier4_simulated_clock_rviz_plugin/CMakeLists.txt +++ /dev/null @@ -1,28 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(tier4_simulated_clock_rviz_plugin) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -find_package(Qt5 REQUIRED Core Widgets) -set(QT_LIBRARIES Qt5::Widgets) -set(CMAKE_AUTOMOC ON) -set(CMAKE_INCLUDE_CURRENT_DIR ON) -add_definitions(-DQT_NO_KEYWORDS) - -ament_auto_add_library(${PROJECT_NAME} SHARED - src/simulated_clock_panel.cpp -) - -target_link_libraries(${PROJECT_NAME} - ${QT_LIBRARIES} -) - -# 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/common/tier4_simulated_clock_rviz_plugin/README.md b/common/tier4_simulated_clock_rviz_plugin/README.md deleted file mode 100644 index 73e53b69279ff..0000000000000 --- a/common/tier4_simulated_clock_rviz_plugin/README.md +++ /dev/null @@ -1,27 +0,0 @@ -# tier4_simulated_clock_rviz_plugin - -## Purpose - -This plugin allows publishing and controlling the simulated ROS time. - -## Output - -| Name | Type | Description | -| -------- | --------------------------- | -------------------------- | -| `/clock` | `rosgraph_msgs::msg::Clock` | the current simulated time | - -## HowToUse - -1. Start rviz and select panels/Add new panel. - ![select_panel](./images/select_panels.png) -2. Select tier4_clock_rviz_plugin/SimulatedClock and press OK. - ![select_clock_plugin](./images/select_clock_plugin.png) -3. Use the added panel to control how the simulated clock is published. - ![use_clock_plugin](./images/use_clock_plugin.png) - - - Pause button: pause/resume the clock. - - Speed: speed of the clock relative to the system clock. - - Rate: publishing rate of the clock. - - Step button: advance the clock by the specified time step. - - Time step: value used to advance the clock when pressing the step button d). - - Time unit: time unit associated with the value from e). diff --git a/common/tier4_simulated_clock_rviz_plugin/icons/classes/SimulatedClockPanel.png b/common/tier4_simulated_clock_rviz_plugin/icons/classes/SimulatedClockPanel.png deleted file mode 100644 index 9431c2d422363..0000000000000 Binary files a/common/tier4_simulated_clock_rviz_plugin/icons/classes/SimulatedClockPanel.png and /dev/null differ diff --git a/common/tier4_simulated_clock_rviz_plugin/images/select_clock_plugin.png b/common/tier4_simulated_clock_rviz_plugin/images/select_clock_plugin.png deleted file mode 100644 index 8bf5e3a903751..0000000000000 Binary files a/common/tier4_simulated_clock_rviz_plugin/images/select_clock_plugin.png and /dev/null differ diff --git a/common/tier4_simulated_clock_rviz_plugin/images/select_panels.png b/common/tier4_simulated_clock_rviz_plugin/images/select_panels.png deleted file mode 100644 index a691602c42c3c..0000000000000 Binary files a/common/tier4_simulated_clock_rviz_plugin/images/select_panels.png and /dev/null differ diff --git a/common/tier4_simulated_clock_rviz_plugin/images/use_clock_plugin.png b/common/tier4_simulated_clock_rviz_plugin/images/use_clock_plugin.png deleted file mode 100644 index 39c3669c2ea31..0000000000000 Binary files a/common/tier4_simulated_clock_rviz_plugin/images/use_clock_plugin.png and /dev/null differ diff --git a/common/tier4_simulated_clock_rviz_plugin/package.xml b/common/tier4_simulated_clock_rviz_plugin/package.xml deleted file mode 100644 index d80b18a5895b0..0000000000000 --- a/common/tier4_simulated_clock_rviz_plugin/package.xml +++ /dev/null @@ -1,28 +0,0 @@ - - - - tier4_simulated_clock_rviz_plugin - 0.0.1 - Rviz plugin to publish and control the /clock topic - Maxime CLEMENT - Apache License 2.0 - - ament_cmake_auto - autoware_cmake - - libqt5-core - libqt5-gui - libqt5-widgets - qtbase5-dev - rclcpp - rosgraph_msgs - rviz_common - - ament_lint_auto - autoware_lint_common - - - ament_cmake - - - diff --git a/common/tier4_simulated_clock_rviz_plugin/plugins/plugin_description.xml b/common/tier4_simulated_clock_rviz_plugin/plugins/plugin_description.xml deleted file mode 100644 index 00caf2e5d49e0..0000000000000 --- a/common/tier4_simulated_clock_rviz_plugin/plugins/plugin_description.xml +++ /dev/null @@ -1,9 +0,0 @@ - - - - Panel that publishes a simulated clock to the /clock topic and provides an interface to pause the clock and modify its speed. - - - diff --git a/common/tier4_simulated_clock_rviz_plugin/src/simulated_clock_panel.cpp b/common/tier4_simulated_clock_rviz_plugin/src/simulated_clock_panel.cpp deleted file mode 100644 index ad698d925fdff..0000000000000 --- a/common/tier4_simulated_clock_rviz_plugin/src/simulated_clock_panel.cpp +++ /dev/null @@ -1,153 +0,0 @@ -// -// Copyright 2022 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 "simulated_clock_panel.hpp" - -#include -#include -#include -#include -#include -#include - -#include -#include - -namespace rviz_plugins -{ -SimulatedClockPanel::SimulatedClockPanel(QWidget * parent) : rviz_common::Panel(parent) -{ - pause_button_ = new QPushButton("Pause"); - pause_button_->setToolTip("Freeze ROS time."); - pause_button_->setCheckable(true); - - publishing_rate_input_ = new QSpinBox(); - publishing_rate_input_->setRange(1, 1000); - publishing_rate_input_->setSingleStep(1); - publishing_rate_input_->setValue(100); - publishing_rate_input_->setSuffix("Hz"); - - clock_speed_input_ = new QDoubleSpinBox(); - clock_speed_input_->setRange(0.0, 10.0); - clock_speed_input_->setSingleStep(0.1); - clock_speed_input_->setValue(1.0); - clock_speed_input_->setSuffix(" X real time"); - - step_button_ = new QPushButton("Step"); - step_button_->setToolTip("Pause and steps the simulation clock"); - step_time_input_ = new QSpinBox(); - step_time_input_->setRange(1, 999); - step_time_input_->setValue(1); - step_unit_combo_ = new QComboBox(); - step_unit_combo_->addItems({"s", "ms", "µs", "ns"}); - - auto * layout = new QGridLayout(this); - auto * step_layout = new QHBoxLayout(); - auto * clock_layout = new QHBoxLayout(); - auto * clock_box = new QWidget(); - auto * step_box = new QWidget(); - clock_box->setLayout(clock_layout); - step_box->setLayout(step_layout); - layout->addWidget(pause_button_, 0, 0); - layout->addWidget(step_button_, 1, 0); - clock_layout->addWidget(new QLabel("Speed:")); - clock_layout->addWidget(clock_speed_input_); - clock_layout->addWidget(new QLabel("Rate:")); - clock_layout->addWidget(publishing_rate_input_); - step_layout->addWidget(step_time_input_); - step_layout->addWidget(step_unit_combo_); - layout->addWidget(clock_box, 0, 1, 1, 2); - layout->addWidget(step_box, 1, 1, 1, 2); - layout->setContentsMargins(0, 0, 20, 0); - prev_published_time_ = std::chrono::system_clock::now(); - - connect(publishing_rate_input_, SIGNAL(valueChanged(int)), this, SLOT(onRateChanged(int))); - connect(step_button_, SIGNAL(clicked()), this, SLOT(onStepClicked())); -} - -void SimulatedClockPanel::onInitialize() -{ - raw_node_ = this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); - - clock_pub_ = raw_node_->create_publisher("/clock", rclcpp::QoS(1)); - createWallTimer(); -} - -void SimulatedClockPanel::onRateChanged(int new_rate) -{ - (void)new_rate; - pub_timer_->cancel(); - createWallTimer(); -} - -void SimulatedClockPanel::onStepClicked() -{ - using std::chrono::duration_cast, std::chrono::seconds, std::chrono::milliseconds, - std::chrono::microseconds, std::chrono::nanoseconds; - pause_button_->setChecked(true); - const auto step_time = step_time_input_->value(); - const auto unit = step_unit_combo_->currentText(); - nanoseconds step_duration_ns{}; - if (unit == "s") { - step_duration_ns += duration_cast(seconds(step_time)); - } else if (unit == "ms") { - step_duration_ns += duration_cast(milliseconds(step_time)); - } else if (unit == "µs") { - step_duration_ns += duration_cast(microseconds(step_time)); - } else if (unit == "ns") { - step_duration_ns += duration_cast(nanoseconds(step_time)); - } - addTimeToClock(step_duration_ns); -} - -void SimulatedClockPanel::createWallTimer() -{ - // convert rate from Hz to milliseconds - const auto period = - std::chrono::milliseconds(static_cast(1e3 / publishing_rate_input_->value())); - pub_timer_ = raw_node_->create_wall_timer(period, [&]() { onTimer(); }); -} - -void SimulatedClockPanel::onTimer() -{ - if (!pause_button_->isChecked()) { - const auto duration_since_prev_clock = std::chrono::system_clock::now() - prev_published_time_; - const auto speed_adjusted_duration = duration_since_prev_clock * clock_speed_input_->value(); - addTimeToClock(std::chrono::duration_cast(speed_adjusted_duration)); - } - clock_pub_->publish(clock_msg_); - prev_published_time_ = std::chrono::system_clock::now(); -} - -void SimulatedClockPanel::addTimeToClock(std::chrono::nanoseconds time_to_add_ns) -{ - constexpr auto one_sec = std::chrono::seconds(1); - constexpr auto one_sec_ns = std::chrono::nanoseconds(one_sec); - while (time_to_add_ns >= one_sec) { - time_to_add_ns -= one_sec; - clock_msg_.clock.sec += 1; - } - clock_msg_.clock.nanosec += time_to_add_ns.count(); - if (clock_msg_.clock.nanosec >= one_sec_ns.count()) { - clock_msg_.clock.sec += 1; - clock_msg_.clock.nanosec = clock_msg_.clock.nanosec - one_sec_ns.count(); - } -} - -} // namespace rviz_plugins - -#include -PLUGINLIB_EXPORT_CLASS(rviz_plugins::SimulatedClockPanel, rviz_common::Panel) diff --git a/common/tier4_simulated_clock_rviz_plugin/src/simulated_clock_panel.hpp b/common/tier4_simulated_clock_rviz_plugin/src/simulated_clock_panel.hpp deleted file mode 100644 index b2ac332107202..0000000000000 --- a/common/tier4_simulated_clock_rviz_plugin/src/simulated_clock_panel.hpp +++ /dev/null @@ -1,76 +0,0 @@ -// -// Copyright 2022 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 SIMULATED_CLOCK_PANEL_HPP_ -#define SIMULATED_CLOCK_PANEL_HPP_ - -#include -#include -#include -#include -#include -#include -#include - -#include - -#include - -namespace rviz_plugins -{ -class SimulatedClockPanel : public rviz_common::Panel -{ - Q_OBJECT - -public: - explicit SimulatedClockPanel(QWidget * parent = nullptr); - void onInitialize() override; - -protected Q_SLOTS: - /// @brief callback for when the publishing rate is changed - void onRateChanged(int new_rate); - /// @brief callback for when the step button is clicked - void onStepClicked(); - -protected: - /// @brief creates ROS wall timer to periodically call onTimer() - void createWallTimer(); - void onTimer(); - /// @brief add some time to the clock - /// @input ns time to add in nanoseconds - void addTimeToClock(std::chrono::nanoseconds ns); - - // ROS - rclcpp::Node::SharedPtr raw_node_; - rclcpp::Publisher::SharedPtr clock_pub_; - rclcpp::TimerBase::SharedPtr pub_timer_; - - // GUI - QPushButton * pause_button_; - QPushButton * step_button_; - QSpinBox * publishing_rate_input_; - QDoubleSpinBox * clock_speed_input_; - QSpinBox * step_time_input_; - QComboBox * step_unit_combo_; - - // Clocks - std::chrono::time_point prev_published_time_; - rosgraph_msgs::msg::Clock clock_msg_; -}; - -} // namespace rviz_plugins - -#endif // SIMULATED_CLOCK_PANEL_HPP_ diff --git a/common/tier4_state_rviz_plugin/CMakeLists.txt b/common/tier4_state_rviz_plugin/CMakeLists.txt index afe21f66291b2..6b569ddb6d162 100644 --- a/common/tier4_state_rviz_plugin/CMakeLists.txt +++ b/common/tier4_state_rviz_plugin/CMakeLists.txt @@ -13,8 +13,32 @@ add_definitions(-DQT_NO_KEYWORDS) ament_auto_add_library(${PROJECT_NAME} SHARED src/autoware_state_panel.cpp src/velocity_steering_factors_panel.cpp + src/custom_toggle_switch.cpp + src/custom_slider.cpp + src/custom_container.cpp + src/custom_button.cpp + src/custom_icon_label.cpp + src/custom_segmented_button.cpp + src/custom_segmented_button_item.cpp + src/custom_label.cpp + src/include/material_colors.hpp + src/include/autoware_state_panel.hpp + src/include/custom_button.hpp + src/include/custom_container.hpp + src/include/custom_icon_label.hpp + src/include/custom_label.hpp + src/include/custom_segmented_button_item.hpp + src/include/custom_segmented_button.hpp + src/include/custom_slider.hpp + src/include/custom_toggle_switch.hpp + src/include/velocity_steering_factors_panel.hpp ) +target_include_directories( + ${PROJECT_NAME} PUBLIC +) + + target_link_libraries(${PROJECT_NAME} ${QT_LIBRARIES} ) @@ -22,6 +46,9 @@ target_link_libraries(${PROJECT_NAME} # 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 diff --git a/common/tier4_state_rviz_plugin/icons/assets/active.png b/common/tier4_state_rviz_plugin/icons/assets/active.png new file mode 100644 index 0000000000000..db9c81211abd5 Binary files /dev/null and b/common/tier4_state_rviz_plugin/icons/assets/active.png differ diff --git a/common/tier4_state_rviz_plugin/icons/assets/crash.png b/common/tier4_state_rviz_plugin/icons/assets/crash.png new file mode 100644 index 0000000000000..18175a823ae4a Binary files /dev/null and b/common/tier4_state_rviz_plugin/icons/assets/crash.png differ diff --git a/common/tier4_state_rviz_plugin/icons/assets/danger.png b/common/tier4_state_rviz_plugin/icons/assets/danger.png new file mode 100644 index 0000000000000..baed346deea2d Binary files /dev/null and b/common/tier4_state_rviz_plugin/icons/assets/danger.png differ diff --git a/common/tier4_state_rviz_plugin/icons/assets/none.png b/common/tier4_state_rviz_plugin/icons/assets/none.png new file mode 100644 index 0000000000000..c44f9f485dbf1 Binary files /dev/null and b/common/tier4_state_rviz_plugin/icons/assets/none.png differ diff --git a/common/tier4_state_rviz_plugin/icons/assets/pending.png b/common/tier4_state_rviz_plugin/icons/assets/pending.png new file mode 100644 index 0000000000000..3925162878fd5 Binary files /dev/null and b/common/tier4_state_rviz_plugin/icons/assets/pending.png differ diff --git a/common/tier4_state_rviz_plugin/package.xml b/common/tier4_state_rviz_plugin/package.xml index 06d57bd947af3..1db152e9632f8 100644 --- a/common/tier4_state_rviz_plugin/package.xml +++ b/common/tier4_state_rviz_plugin/package.xml @@ -6,6 +6,7 @@ The autoware state rviz plugin package Hiroki OTA Takagi, Isamu + Khalil Selyan Apache License 2.0 ament_cmake_auto diff --git a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp index ba961b9ac5b00..f9fb7d3dd3958 100644 --- a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp +++ b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp @@ -14,15 +14,13 @@ // limitations under the License. // -#include "autoware_state_panel.hpp" +#include "include/autoware_state_panel.hpp" -#include -#include -#include -#include -#include #include +#include +#include + #include #include @@ -35,181 +33,59 @@ namespace rviz_plugins { AutowareStatePanel::AutowareStatePanel(QWidget * parent) : rviz_common::Panel(parent) { - // Gear - auto * gear_prefix_label_ptr = new QLabel("GEAR: "); - gear_prefix_label_ptr->setAlignment(Qt::AlignRight | Qt::AlignVCenter); - gear_label_ptr_ = new QLabel("INIT"); - gear_label_ptr_->setAlignment(Qt::AlignCenter); - auto * gear_layout = new QHBoxLayout; - gear_layout->addWidget(gear_prefix_label_ptr); - gear_layout->addWidget(gear_label_ptr_); - - // Velocity Limit - velocity_limit_button_ptr_ = new QPushButton("Send Velocity Limit"); - pub_velocity_limit_input_ = new QSpinBox(); - pub_velocity_limit_input_->setRange(-100.0, 100.0); - pub_velocity_limit_input_->setValue(0.0); - pub_velocity_limit_input_->setSingleStep(5.0); - connect(velocity_limit_button_ptr_, SIGNAL(clicked()), this, SLOT(onClickVelocityLimit())); - - // Emergency Button - emergency_button_ptr_ = new QPushButton("Set Emergency"); - connect(emergency_button_ptr_, SIGNAL(clicked()), this, SLOT(onClickEmergencyButton())); + // Panel Configuration + this->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding); // Layout - auto * v_layout = new QVBoxLayout; - auto * velocity_limit_layout = new QHBoxLayout(); - v_layout->addWidget(makeOperationModeGroup()); - v_layout->addWidget(makeControlModeGroup()); - { - auto * h_layout = new QHBoxLayout(); - h_layout->addWidget(makeRoutingGroup()); - h_layout->addWidget(makeLocalizationGroup()); - h_layout->addWidget(makeMotionGroup()); - h_layout->addWidget(makeFailSafeGroup()); - v_layout->addLayout(h_layout); - } - - v_layout->addLayout(gear_layout); - velocity_limit_layout->addWidget(velocity_limit_button_ptr_); - velocity_limit_layout->addWidget(pub_velocity_limit_input_); - velocity_limit_layout->addWidget(new QLabel(" [km/h]")); - velocity_limit_layout->addWidget(emergency_button_ptr_); - v_layout->addLayout(velocity_limit_layout); - setLayout(v_layout); -} - -QGroupBox * AutowareStatePanel::makeOperationModeGroup() -{ - auto * group = new QGroupBox("OperationMode"); - auto * grid = new QGridLayout; - - operation_mode_label_ptr_ = new QLabel("INIT"); - operation_mode_label_ptr_->setAlignment(Qt::AlignCenter); - operation_mode_label_ptr_->setStyleSheet("border:1px solid black;"); - grid->addWidget(operation_mode_label_ptr_, 0, 0, 0, 1); - - auto_button_ptr_ = new QPushButton("AUTO"); - auto_button_ptr_->setCheckable(true); - connect(auto_button_ptr_, SIGNAL(clicked()), SLOT(onClickAutonomous())); - grid->addWidget(auto_button_ptr_, 0, 1); - - stop_button_ptr_ = new QPushButton("STOP"); - stop_button_ptr_->setCheckable(true); - connect(stop_button_ptr_, SIGNAL(clicked()), SLOT(onClickStop())); - grid->addWidget(stop_button_ptr_, 0, 2); - - local_button_ptr_ = new QPushButton("LOCAL"); - local_button_ptr_->setCheckable(true); - connect(local_button_ptr_, SIGNAL(clicked()), SLOT(onClickLocal())); - grid->addWidget(local_button_ptr_, 1, 1); - - remote_button_ptr_ = new QPushButton("REMOTE"); - remote_button_ptr_->setCheckable(true); - connect(remote_button_ptr_, SIGNAL(clicked()), SLOT(onClickRemote())); - grid->addWidget(remote_button_ptr_, 1, 2); - - group->setLayout(grid); - return group; -} - -QGroupBox * AutowareStatePanel::makeControlModeGroup() -{ - auto * group = new QGroupBox("AutowareControl"); - auto * grid = new QGridLayout; - - control_mode_label_ptr_ = new QLabel("INIT"); - control_mode_label_ptr_->setAlignment(Qt::AlignCenter); - control_mode_label_ptr_->setStyleSheet("border:1px solid black;"); - grid->addWidget(control_mode_label_ptr_, 0, 0); - - enable_button_ptr_ = new QPushButton("Enable"); - enable_button_ptr_->setCheckable(true); - connect(enable_button_ptr_, SIGNAL(clicked()), SLOT(onClickAutowareControl())); - grid->addWidget(enable_button_ptr_, 0, 1); - - disable_button_ptr_ = new QPushButton("Disable"); - disable_button_ptr_->setCheckable(true); - connect(disable_button_ptr_, SIGNAL(clicked()), SLOT(onClickDirectControl())); - grid->addWidget(disable_button_ptr_, 0, 2); - - group->setLayout(grid); - return group; -} - -QGroupBox * AutowareStatePanel::makeRoutingGroup() -{ - auto * group = new QGroupBox("Routing"); - auto * grid = new QGridLayout; - routing_label_ptr_ = new QLabel("INIT"); - routing_label_ptr_->setAlignment(Qt::AlignCenter); - routing_label_ptr_->setStyleSheet("border:1px solid black;"); - grid->addWidget(routing_label_ptr_, 0, 0); - - clear_route_button_ptr_ = new QPushButton("Clear Route"); - clear_route_button_ptr_->setCheckable(true); - connect(clear_route_button_ptr_, SIGNAL(clicked()), SLOT(onClickClearRoute())); - grid->addWidget(clear_route_button_ptr_, 1, 0); - - group->setLayout(grid); - return group; -} - -QGroupBox * AutowareStatePanel::makeLocalizationGroup() -{ - auto * group = new QGroupBox("Localization"); - auto * grid = new QGridLayout; - - localization_label_ptr_ = new QLabel("INIT"); - localization_label_ptr_->setAlignment(Qt::AlignCenter); - localization_label_ptr_->setStyleSheet("border:1px solid black;"); - grid->addWidget(localization_label_ptr_, 0, 0); - - init_by_gnss_button_ptr_ = new QPushButton("Init by GNSS"); - connect(init_by_gnss_button_ptr_, SIGNAL(clicked()), SLOT(onClickInitByGnss())); - grid->addWidget(init_by_gnss_button_ptr_, 1, 0); - - group->setLayout(grid); - return group; -} - -QGroupBox * AutowareStatePanel::makeMotionGroup() -{ - auto * group = new QGroupBox("Motion"); - auto * grid = new QGridLayout; - - motion_label_ptr_ = new QLabel("INIT"); - motion_label_ptr_->setAlignment(Qt::AlignCenter); - motion_label_ptr_->setStyleSheet("border:1px solid black;"); - grid->addWidget(motion_label_ptr_, 0, 0); - - accept_start_button_ptr_ = new QPushButton("Accept Start"); - accept_start_button_ptr_->setCheckable(true); - connect(accept_start_button_ptr_, SIGNAL(clicked()), SLOT(onClickAcceptStart())); - grid->addWidget(accept_start_button_ptr_, 1, 0); - - group->setLayout(grid); - return group; -} - -QGroupBox * AutowareStatePanel::makeFailSafeGroup() -{ - auto * group = new QGroupBox("FailSafe"); - auto * grid = new QGridLayout; - - mrm_state_label_ptr_ = new QLabel("INIT"); - mrm_state_label_ptr_->setAlignment(Qt::AlignCenter); - mrm_state_label_ptr_->setStyleSheet("border:1px solid black;"); - grid->addWidget(mrm_state_label_ptr_, 0, 0); - - mrm_behavior_label_ptr_ = new QLabel("INIT"); - mrm_behavior_label_ptr_->setAlignment(Qt::AlignCenter); - mrm_behavior_label_ptr_->setStyleSheet("border:1px solid black;"); - grid->addWidget(mrm_behavior_label_ptr_, 1, 0); - - group->setLayout(grid); - return group; + // Create a new container widget + QWidget * containerWidget = new QWidget(this); + containerWidget->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding); + + containerWidget->setStyleSheet( + QString("QWidget { background-color: %1; color: %2; }") + .arg(autoware::state_rviz_plugin::colors::default_colors.background.c_str()) + .arg(autoware::state_rviz_plugin::colors::default_colors.on_surface.c_str())); + + auto * containerLayout = new QVBoxLayout(containerWidget); + // Set the alignment of the layout + containerLayout->setAlignment(Qt::AlignTop); + containerLayout->setSpacing(1); + + auto * operation_mode_group = makeOperationModeGroup(); + auto * diagnostic_v_layout = new QVBoxLayout; + auto * localization_group = makeLocalizationGroup(); + auto * motion_group = makeMotionGroup(); + auto * fail_safe_group = makeFailSafeGroup(); + auto * routing_group = makeRoutingGroup(); + auto * velocity_limit_group = makeVelocityLimitGroup(); + // auto * diagnostic_group = makeDiagnosticGroup(); + + diagnostic_v_layout->addLayout(routing_group); + // diagnostic_v_layout->addSpacing(5); + diagnostic_v_layout->addLayout(localization_group); + // diagnostic_v_layout->addSpacing(5); + diagnostic_v_layout->addLayout(motion_group); + // diagnostic_v_layout->addSpacing(5); + diagnostic_v_layout->addLayout(fail_safe_group); + + // containerLayout->addLayout(diagnostic_group); + + containerLayout->addLayout(operation_mode_group); + // containerLayout->addSpacing(5); + containerLayout->addLayout(diagnostic_v_layout); + // main_v_layout->addSpacing(5); + containerLayout->addLayout(velocity_limit_group); + + // Create a QScrollArea + QScrollArea * scrollArea = new QScrollArea(this); + scrollArea->setWidgetResizable(true); + scrollArea->setWidget(containerWidget); + + // Main layout for AutowareStatePanel + QVBoxLayout * mainLayout = new QVBoxLayout(this); + mainLayout->addWidget(scrollArea); + setLayout(mainLayout); } void AutowareStatePanel::onInitialize() @@ -268,9 +144,9 @@ void AutowareStatePanel::onInitialize() "/api/fail_safe/mrm_state", rclcpp::QoS{1}.transient_local(), std::bind(&AutowareStatePanel::onMRMState, this, _1)); - // Others - sub_gear_ = raw_node_->create_subscription( - "/vehicle/status/gear_status", 10, std::bind(&AutowareStatePanel::onShift, this, _1)); + // // Diagnostics + // sub_diag_ = raw_node_->create_subscription( + // "/diagnostics", 10, std::bind(&AutowareStatePanel::onDiagnostics, this, _1)); sub_emergency_ = raw_node_->create_subscription( "/api/autoware/get/emergency", 10, std::bind(&AutowareStatePanel::onEmergencyStatus, this, _1)); @@ -280,174 +156,498 @@ void AutowareStatePanel::onInitialize() pub_velocity_limit_ = raw_node_->create_publisher( "/planning/scenario_planning/max_velocity_default", rclcpp::QoS{1}.transient_local()); -} -void AutowareStatePanel::onOperationMode(const OperationModeState::ConstSharedPtr msg) -{ - auto changeButtonState = [this]( - QPushButton * button, const bool is_desired_mode_available, - const uint8_t current_mode = OperationModeState::UNKNOWN, - const uint8_t desired_mode = OperationModeState::STOP) { - if (is_desired_mode_available && current_mode != desired_mode) { - activateButton(button); + QObject::connect(segmented_button, &CustomSegmentedButton::buttonClicked, this, [this](int id) { + const QList buttons = segmented_button->getButtonGroup()->buttons(); + + // Check if the button ID is within valid range + if (id < 0 || id >= buttons.size()) { + return; + } + + // Ensure the button is not null + QAbstractButton * abstractButton = segmented_button->getButtonGroup()->button(id); + if (!abstractButton) { + return; + } + + QPushButton * button = qobject_cast(abstractButton); + if (button) { + // Call the corresponding function for each button + if (button == auto_button_ptr_) { + onClickAutonomous(); + } else if (button == local_button_ptr_) { + onClickLocal(); + } else if (button == remote_button_ptr_) { + onClickRemote(); + } else if (button == stop_button_ptr_) { + onClickStop(); + } } else { - deactivateButton(button); + // qDebug() << "Button not found with ID:" << id; } - }; + }); +} - QString text = ""; - QString style_sheet = ""; - // Operation Mode - switch (msg->mode) { - case OperationModeState::AUTONOMOUS: - text = "AUTONOMOUS"; - style_sheet = "background-color: #00FF00;"; // green - break; +QVBoxLayout * AutowareStatePanel::makeOperationModeGroup() +{ + control_mode_switch_ptr_ = new CustomToggleSwitch(this); + connect( + control_mode_switch_ptr_, &QCheckBox::stateChanged, this, + &AutowareStatePanel::onSwitchStateChanged); + + control_mode_label_ptr_ = new QLabel("Autoware Control"); + control_mode_label_ptr_->setStyleSheet( + QString("color: %1; font-weight: bold;") + .arg(autoware::state_rviz_plugin::colors::default_colors.on_secondary_container.c_str())); + + CustomContainer * group1 = new CustomContainer(this); + + auto * horizontal_layout = new QHBoxLayout; + horizontal_layout->setSpacing(10); + horizontal_layout->setContentsMargins(0, 0, 0, 0); + + horizontal_layout->addWidget(control_mode_switch_ptr_); + horizontal_layout->addWidget(control_mode_label_ptr_); + + // add switch and label to the container + group1->setContentsMargins(0, 0, 0, 10); + group1->getLayout()->addLayout(horizontal_layout, 0, 0, 1, 1, Qt::AlignLeft); + + // Create the CustomSegmentedButton + segmented_button = new CustomSegmentedButton(this); + auto_button_ptr_ = segmented_button->addButton("Auto"); + local_button_ptr_ = segmented_button->addButton("Local"); + remote_button_ptr_ = segmented_button->addButton("Remote"); + stop_button_ptr_ = segmented_button->addButton("Stop"); + + QVBoxLayout * groupLayout = new QVBoxLayout; + // set these widgets to show up at the left and not stretch more than needed + groupLayout->setAlignment(Qt::AlignCenter); + groupLayout->setContentsMargins(10, 0, 0, 0); + groupLayout->addWidget(group1); + // groupLayout->addSpacing(5); + groupLayout->addWidget(segmented_button, 0, Qt::AlignCenter); + return groupLayout; +} - case OperationModeState::LOCAL: - text = "LOCAL"; - style_sheet = "background-color: #FFFF00;"; // yellow - break; +QVBoxLayout * AutowareStatePanel::makeRoutingGroup() +{ + auto * group = new QVBoxLayout; - case OperationModeState::REMOTE: - text = "REMOTE"; - style_sheet = "background-color: #FFFF00;"; // yellow - break; + auto * custom_container = new CustomContainer(this); - case OperationModeState::STOP: - text = "STOP"; - style_sheet = "background-color: #FFA500;"; // orange - break; + routing_icon = new CustomIconLabel( + QColor(autoware::state_rviz_plugin::colors::default_colors.primary.c_str())); - default: - text = "UNKNOWN"; - style_sheet = "background-color: #FF0000;"; // red - break; - } + clear_route_button_ptr_ = new CustomElevatedButton("Clear Route"); + clear_route_button_ptr_->setCheckable(true); + clear_route_button_ptr_->setCursor(Qt::PointingHandCursor); + connect(clear_route_button_ptr_, SIGNAL(clicked()), SLOT(onClickClearRoute())); - if (msg->is_in_transition) { - text += "\n(TRANSITION)"; - } + routing_label_ptr_ = new QLabel("Routing | Unknown"); + routing_label_ptr_->setStyleSheet( + QString("color: %1; font-weight: bold;") + .arg(autoware::state_rviz_plugin::colors::default_colors.on_secondary_container.c_str())); - updateLabel(operation_mode_label_ptr_, text, style_sheet); + auto * horizontal_layout = new QHBoxLayout; + horizontal_layout->setSpacing(10); + horizontal_layout->setContentsMargins(0, 0, 0, 0); - // Control Mode - if (msg->is_autoware_control_enabled) { - updateLabel(control_mode_label_ptr_, "Enable", "background-color: #00FF00;"); // green - } else { - updateLabel(control_mode_label_ptr_, "Disable", "background-color: #FFFF00;"); // yellow - } + horizontal_layout->addWidget(routing_icon); + horizontal_layout->addWidget(routing_label_ptr_); + + custom_container->getLayout()->addLayout(horizontal_layout, 0, 0, 1, 1, Qt::AlignLeft); + custom_container->getLayout()->addWidget(clear_route_button_ptr_, 0, 2, 1, 4, Qt::AlignRight); + + custom_container->setContentsMargins(10, 0, 0, 0); + + group->addWidget(custom_container); + + return group; +} - // Button - changeButtonState( - auto_button_ptr_, msg->is_autonomous_mode_available, msg->mode, OperationModeState::AUTONOMOUS); - changeButtonState( - stop_button_ptr_, msg->is_stop_mode_available, msg->mode, OperationModeState::STOP); - changeButtonState( - local_button_ptr_, msg->is_local_mode_available, msg->mode, OperationModeState::LOCAL); - changeButtonState( - remote_button_ptr_, msg->is_remote_mode_available, msg->mode, OperationModeState::REMOTE); - - changeButtonState(enable_button_ptr_, !msg->is_autoware_control_enabled); - changeButtonState(disable_button_ptr_, msg->is_autoware_control_enabled); +QVBoxLayout * AutowareStatePanel::makeLocalizationGroup() +{ + auto * group = new QVBoxLayout; + auto * custom_container = new CustomContainer(this); + + init_by_gnss_button_ptr_ = new CustomElevatedButton("Initialize with GNSS"); + init_by_gnss_button_ptr_->setCursor(Qt::PointingHandCursor); + connect(init_by_gnss_button_ptr_, SIGNAL(clicked()), SLOT(onClickInitByGnss())); + + localization_icon = new CustomIconLabel( + QColor(autoware::state_rviz_plugin::colors::default_colors.primary.c_str())); + localization_label_ptr_ = new QLabel("Localization | Unknown"); + localization_label_ptr_->setStyleSheet( + QString("color: %1; font-weight: bold;") + .arg(autoware::state_rviz_plugin::colors::default_colors.on_secondary_container.c_str())); + + auto * horizontal_layout = new QHBoxLayout; + horizontal_layout->setSpacing(10); + horizontal_layout->setContentsMargins(0, 0, 0, 0); + + horizontal_layout->addWidget(localization_icon); + horizontal_layout->addWidget(localization_label_ptr_); + + custom_container->getLayout()->addLayout(horizontal_layout, 0, 0, 1, 1, Qt::AlignLeft); + custom_container->getLayout()->addWidget(init_by_gnss_button_ptr_, 0, 2, 1, 4, Qt::AlignRight); + + custom_container->setContentsMargins(10, 0, 0, 0); + + group->addWidget(custom_container); + return group; +} + +QVBoxLayout * AutowareStatePanel::makeMotionGroup() +{ + auto * group = new QVBoxLayout; + auto * custom_container = new CustomContainer(this); + + accept_start_button_ptr_ = new CustomElevatedButton("Accept Start"); + accept_start_button_ptr_->setCheckable(true); + accept_start_button_ptr_->setCursor(Qt::PointingHandCursor); + connect(accept_start_button_ptr_, SIGNAL(clicked()), SLOT(onClickAcceptStart())); + + motion_icon = new CustomIconLabel( + QColor(autoware::state_rviz_plugin::colors::default_colors.primary.c_str())); + motion_label_ptr_ = new QLabel("Motion | Unknown"); + motion_label_ptr_->setStyleSheet( + QString("color: %1; font-weight: bold;") + .arg(autoware::state_rviz_plugin::colors::default_colors.on_secondary_container.c_str())); + + auto * horizontal_layout = new QHBoxLayout; + horizontal_layout->setSpacing(10); + horizontal_layout->setContentsMargins(0, 0, 0, 0); + horizontal_layout->setAlignment(Qt::AlignLeft); + + horizontal_layout->addWidget(motion_icon); + horizontal_layout->addWidget(motion_label_ptr_); + + custom_container->getLayout()->addLayout(horizontal_layout, 0, 0, 1, 1, Qt::AlignLeft); + custom_container->getLayout()->addWidget(accept_start_button_ptr_, 0, 2, 1, 4, Qt::AlignRight); + + custom_container->setContentsMargins(10, 0, 0, 0); + + group->addWidget(custom_container); + + return group; +} + +QVBoxLayout * AutowareStatePanel::makeFailSafeGroup() +{ + auto * group = new QVBoxLayout; + auto * v_layout = new QVBoxLayout; + auto * custom_container1 = new CustomContainer(this); + auto * custom_container2 = new CustomContainer(this); + + mrm_state_icon = new CustomIconLabel( + QColor(autoware::state_rviz_plugin::colors::default_colors.primary.c_str())); + mrm_behavior_icon = new CustomIconLabel( + QColor(autoware::state_rviz_plugin::colors::default_colors.primary.c_str())); + + mrm_state_label_ptr_ = new QLabel("MRM State | Unknown"); + mrm_behavior_label_ptr_ = new QLabel("MRM Behavior | Unknown"); + + // change text color + mrm_state_label_ptr_->setStyleSheet( + QString("color: %1; font-weight: bold;") + .arg(autoware::state_rviz_plugin::colors::default_colors.on_secondary_container.c_str())); + mrm_behavior_label_ptr_->setStyleSheet( + QString("color: %1; font-weight: bold;") + .arg(autoware::state_rviz_plugin::colors::default_colors.on_secondary_container.c_str())); + + auto * horizontal_layout = new QHBoxLayout; + horizontal_layout->setSpacing(10); + horizontal_layout->setContentsMargins(0, 0, 0, 0); + + horizontal_layout->addWidget(mrm_state_icon); + horizontal_layout->addWidget(mrm_state_label_ptr_); + + custom_container1->getLayout()->addLayout(horizontal_layout, 0, 0, 1, 1, Qt::AlignLeft); + + auto * horizontal_layout2 = new QHBoxLayout; + horizontal_layout2->setSpacing(10); + horizontal_layout2->setContentsMargins(0, 0, 0, 0); + + horizontal_layout2->addWidget(mrm_behavior_icon); + horizontal_layout2->addWidget(mrm_behavior_label_ptr_); + + custom_container2->getLayout()->addLayout(horizontal_layout2, 0, 0, 1, 1, Qt::AlignLeft); + + v_layout->addWidget(custom_container1); + // v_layout->addSpacing(5); + v_layout->addWidget(custom_container2); + + group->setContentsMargins(10, 0, 0, 0); + + group->addLayout(v_layout); + return group; +} + +/* QVBoxLayout * AutowareStatePanel::makeDiagnosticGroup() +{ + auto * group = new QVBoxLayout; + + // Create the scroll area + QScrollArea * scrollArea = new QScrollArea; + scrollArea->setFixedHeight(66); // Adjust the height as needed + scrollArea->setWidgetResizable(true); + scrollArea->setHorizontalScrollBarPolicy(Qt::ScrollBarAsNeeded); + scrollArea->setVerticalScrollBarPolicy(Qt::ScrollBarAsNeeded); + + // Create a widget to contain the layout + QWidget * scrollAreaWidgetContents = new QWidget; + // use layout to contain the diagnostic label and the diagnostic level + diagnostic_layout_ = new QVBoxLayout(); + diagnostic_layout_->setSpacing(5); // Set space between items + diagnostic_layout_->setContentsMargins(5, 5, 5, 5); // Set margins within the layout + + // Add a QLabel to display the title of what this is + auto * tsm_label_title_ptr_ = new QLabel("Topic State Monitor: "); + // Set the layout on the widget + scrollAreaWidgetContents->setLayout(diagnostic_layout_); + + // Set the widget on the scroll area + scrollArea->setWidget(scrollAreaWidgetContents); + + group->addWidget(tsm_label_title_ptr_); + group->addWidget(scrollArea); + + return group; +} */ + +QVBoxLayout * AutowareStatePanel::makeVelocityLimitGroup() +{ + // Velocity Limit + velocity_limit_setter_ptr_ = new QLabel("Set Velocity Limit"); + // set its width to fit the text + velocity_limit_setter_ptr_->setFixedWidth( + velocity_limit_setter_ptr_->fontMetrics().horizontalAdvance("Set Velocity Limit")); + + velocity_limit_value_label_ = new QLabel("0"); + velocity_limit_value_label_->setMaximumWidth( + velocity_limit_value_label_->fontMetrics().horizontalAdvance("0")); + + CustomSlider * pub_velocity_limit_slider_ = new CustomSlider(Qt::Horizontal); + pub_velocity_limit_slider_->setRange(0, 100); + pub_velocity_limit_slider_->setValue(0); + pub_velocity_limit_slider_->setMaximumWidth(300); + + connect(pub_velocity_limit_slider_, &QSlider::sliderPressed, this, [this]() { + sliderIsDragging = true; // User starts dragging the handle + }); + + connect(pub_velocity_limit_slider_, &QSlider::sliderReleased, this, [this]() { + sliderIsDragging = false; // User finished dragging + onClickVelocityLimit(); // Call when handle is released after dragging + }); + + connect(pub_velocity_limit_slider_, &QSlider::valueChanged, this, [this](int value) { + this->velocity_limit_value_label_->setText(QString::number(value)); + velocity_limit_value_label_->setMaximumWidth( + velocity_limit_value_label_->fontMetrics().horizontalAdvance(QString::number(value))); + if (!sliderIsDragging) { // If the value changed without dragging, it's a click on the track + onClickVelocityLimit(); // Call the function immediately since it's not a drag operation + } + }); + + // Emergency Button + emergency_button_ptr_ = new CustomElevatedButton("Set Emergency"); + + emergency_button_ptr_->setCursor(Qt::PointingHandCursor); + // set fixed width to fit the text + connect(emergency_button_ptr_, SIGNAL(clicked()), this, SLOT(onClickEmergencyButton())); + auto * utility_layout = new QVBoxLayout; + auto * velocity_limit_layout = new QHBoxLayout; + QLabel * velocity_limit_label = new QLabel("km/h"); + + velocity_limit_layout->addWidget(pub_velocity_limit_slider_); + velocity_limit_layout->addSpacing(5); + velocity_limit_layout->addWidget(velocity_limit_value_label_); + velocity_limit_layout->addWidget(velocity_limit_label); + + // Velocity Limit layout + utility_layout->addSpacing(15); + utility_layout->addWidget(velocity_limit_setter_ptr_); + utility_layout->addSpacing(10); + utility_layout->addLayout(velocity_limit_layout); + utility_layout->addSpacing(25); + utility_layout->addWidget(emergency_button_ptr_); + + utility_layout->setContentsMargins(15, 0, 15, 0); + + return utility_layout; +} + +void AutowareStatePanel::onOperationMode(const OperationModeState::ConstSharedPtr msg) +{ + auto updateButtonState = []( + CustomSegmentedButtonItem * button, bool is_available, + uint8_t current_mode, uint8_t desired_mode, bool disable) { + bool is_checked = (current_mode == desired_mode); + button->setHovered(false); + + button->setActivated(is_checked); + button->setChecked(is_checked); + button->setDisabledButton(disable || !is_available); + button->setCheckableButton(!disable && is_available && !is_checked); + }; + + bool disable_buttons = msg->is_in_transition; + + updateButtonState( + auto_button_ptr_, msg->is_autonomous_mode_available, msg->mode, OperationModeState::AUTONOMOUS, + disable_buttons); + updateButtonState( + stop_button_ptr_, msg->is_stop_mode_available, msg->mode, OperationModeState::STOP, + disable_buttons); + updateButtonState( + local_button_ptr_, msg->is_local_mode_available, msg->mode, OperationModeState::LOCAL, + disable_buttons); + updateButtonState( + remote_button_ptr_, msg->is_remote_mode_available, msg->mode, OperationModeState::REMOTE, + disable_buttons); + + // toggle switch for control mode + auto changeToggleSwitchState = [](CustomToggleSwitch * toggle_switch, const bool is_enabled) { + // Flick the switch without triggering its function + bool old_state = toggle_switch->blockSignals(true); + toggle_switch->setCheckedState(!is_enabled); + toggle_switch->blockSignals(old_state); + }; + + if (!msg->is_in_transition) { + // would cause an on/off/on flicker if in transition + changeToggleSwitchState(control_mode_switch_ptr_, !msg->is_autoware_control_enabled); + } } void AutowareStatePanel::onRoute(const RouteState::ConstSharedPtr msg) { - QString text = ""; - QString style_sheet = ""; + IconState state; + QColor bgColor; + QString route_state = "Routing | Unknown"; + switch (msg->state) { case RouteState::UNSET: - text = "UNSET"; - style_sheet = "background-color: #FFFF00;"; // yellow + state = Pending; + bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.warning.c_str()); + route_state = "Routing | Unset"; break; case RouteState::SET: - text = "SET"; - style_sheet = "background-color: #00FF00;"; // green + state = Active; + bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.success.c_str()); + route_state = "Routing | Set"; break; case RouteState::ARRIVED: - text = "ARRIVED"; - style_sheet = "background-color: #FFA500;"; // orange + state = Danger; + bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.danger.c_str()); + route_state = "Routing | Arrived"; break; case RouteState::CHANGING: - text = "CHANGING"; - style_sheet = "background-color: #FFFF00;"; // yellow + bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.warning.c_str()); + state = Pending; + route_state = "Routing | Changing"; break; default: - text = "UNKNOWN"; - style_sheet = "background-color: #FF0000;"; // red + state = None; + bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.info.c_str()); break; } - updateLabel(routing_label_ptr_, text, style_sheet); + routing_icon->updateStyle(state, bgColor); + routing_label_ptr_->setText(route_state); if (msg->state == RouteState::SET) { activateButton(clear_route_button_ptr_); } else { + clear_route_button_ptr_->setStyleSheet( + QString("QPushButton {" + "background-color: %1;color: %2;" + "border: 2px solid %3;" + "font-weight: bold;" + "}") + .arg(autoware::state_rviz_plugin::colors::default_colors.surface_container_highest.c_str()) + .arg(autoware::state_rviz_plugin::colors::default_colors.outline.c_str()) + .arg( + autoware::state_rviz_plugin::colors::default_colors.surface_container_highest.c_str())); deactivateButton(clear_route_button_ptr_); } } void AutowareStatePanel::onLocalization(const LocalizationInitializationState::ConstSharedPtr msg) { - QString text = ""; - QString style_sheet = ""; + IconState state; + QColor bgColor; + QString localization_state = "Localization | Unknown"; + switch (msg->state) { case LocalizationInitializationState::UNINITIALIZED: - text = "UNINITIALIZED"; - style_sheet = "background-color: #FFFF00;"; // yellow + state = None; + bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.info.c_str()); + localization_state = "Localization | Uninitialized"; break; - case LocalizationInitializationState::INITIALIZING: - text = "INITIALIZING"; - style_sheet = "background-color: #FFA500;"; // orange + case LocalizationInitializationState::INITIALIZED: + state = Active; + bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.success.c_str()); + localization_state = "Localization | Initialized"; break; - case LocalizationInitializationState::INITIALIZED: - text = "INITIALIZED"; - style_sheet = "background-color: #00FF00;"; // green + case LocalizationInitializationState::INITIALIZING: + state = Pending; + bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.warning.c_str()); + localization_state = "Localization | Initializing"; break; default: - text = "UNKNOWN"; - style_sheet = "background-color: #FF0000;"; // red + state = None; + bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.info.c_str()); break; } - updateLabel(localization_label_ptr_, text, style_sheet); + localization_icon->updateStyle(state, bgColor); + localization_label_ptr_->setText(localization_state); } void AutowareStatePanel::onMotion(const MotionState::ConstSharedPtr msg) { - QString text = ""; - QString style_sheet = ""; + IconState state; + QColor bgColor; + QString motion_state = "Motion | Unknown"; + switch (msg->state) { case MotionState::STARTING: - text = "STARTING"; - style_sheet = "background-color: #FFFF00;"; // yellow + state = Pending; + bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.warning.c_str()); + motion_state = "Motion | Starting"; break; - case MotionState::STOPPED: - text = "STOPPED"; - style_sheet = "background-color: #FFA500;"; // orange + case MotionState::MOVING: + state = Active; + bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.success.c_str()); + motion_state = "Motion | Moving"; break; - case MotionState::MOVING: - text = "MOVING"; - style_sheet = "background-color: #00FF00;"; // green + case MotionState::STOPPED: + state = None; + bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.danger.c_str()); + motion_state = "Motion | Stopped"; break; default: - text = "UNKNOWN"; - style_sheet = "background-color: #FF0000;"; // red + state = Danger; + bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.info.c_str()); break; } - updateLabel(motion_label_ptr_, text, style_sheet); + motion_icon->updateStyle(state, bgColor); + motion_label_ptr_->setText(motion_state); if (msg->state == MotionState::STARTING) { activateButton(accept_start_button_ptr_); @@ -458,94 +658,85 @@ void AutowareStatePanel::onMotion(const MotionState::ConstSharedPtr msg) void AutowareStatePanel::onMRMState(const MRMState::ConstSharedPtr msg) { - // state - { - QString text = ""; - QString style_sheet = ""; - switch (msg->state) { - case MRMState::NONE: - text = "NONE"; - style_sheet = "background-color: #00FF00;"; // green - break; + IconState state; + QColor bgColor; + QString mrm_state = "MRM State | Unknown"; - case MRMState::MRM_OPERATING: - text = "MRM_OPERATING"; - style_sheet = "background-color: #FFA500;"; // orange - break; + switch (msg->state) { + case MRMState::NONE: + state = None; + bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.info.c_str()); + mrm_state = "MRM State | Inactive"; + break; - case MRMState::MRM_SUCCEEDED: - text = "MRM_SUCCEEDED"; - style_sheet = "background-color: #FFFF00;"; // yellow - break; + case MRMState::MRM_OPERATING: + state = Active; + bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.info.c_str()); + mrm_state = "MRM State | Operating"; + break; - case MRMState::MRM_FAILED: - text = "MRM_FAILED"; - style_sheet = "background-color: #FF0000;"; // red - break; + case MRMState::MRM_SUCCEEDED: + state = Active; + bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.success.c_str()); + mrm_state = "MRM State | Successful"; + break; - default: - text = "UNKNOWN"; - style_sheet = "background-color: #FF0000;"; // red - break; - } + case MRMState::MRM_FAILED: + state = Danger; + bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.danger.c_str()); + mrm_state = "MRM State | Failed"; + break; - updateLabel(mrm_state_label_ptr_, text, style_sheet); + default: + state = None; + bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.info.c_str()); + mrm_state = "MRM State | Unknown"; + break; } + mrm_state_icon->updateStyle(state, bgColor); + mrm_state_label_ptr_->setText(mrm_state); + // behavior { - QString text = ""; - QString style_sheet = ""; + IconState state; + QColor bgColor; + QString mrm_behavior = "MRM Behavior | Unknown"; + switch (msg->behavior) { case MRMState::NONE: - text = "NONE"; - style_sheet = "background-color: #00FF00;"; // green + state = Crash; + bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.info.c_str()); + mrm_behavior = "MRM Behavior | Inactive"; break; case MRMState::PULL_OVER: - text = "PULL_OVER"; - style_sheet = "background-color: #FFFF00;"; // yellow + state = Crash; + bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.success.c_str()); + mrm_behavior = "MRM Behavior | Pull Over"; break; case MRMState::COMFORTABLE_STOP: - text = "COMFORTABLE_STOP"; - style_sheet = "background-color: #FFFF00;"; // yellow + state = Crash; + bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.warning.c_str()); + mrm_behavior = "MRM Behavior | Comfortable Stop"; break; case MRMState::EMERGENCY_STOP: - text = "EMERGENCY_STOP"; - style_sheet = "background-color: #FFA500;"; // orange + state = Crash; + bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.danger.c_str()); + mrm_behavior = "MRM Behavior | Emergency Stop"; break; default: - text = "UNKNOWN"; - style_sheet = "background-color: #FF0000;"; // red + state = Crash; + bgColor = QColor(autoware::state_rviz_plugin::colors::default_colors.info.c_str()); + mrm_behavior = "MRM Behavior | Unknown"; break; } - updateLabel(mrm_behavior_label_ptr_, text, style_sheet); - } -} - -void AutowareStatePanel::onShift( - const autoware_auto_vehicle_msgs::msg::GearReport::ConstSharedPtr msg) -{ - switch (msg->report) { - case autoware_auto_vehicle_msgs::msg::GearReport::PARK: - gear_label_ptr_->setText("PARKING"); - break; - case autoware_auto_vehicle_msgs::msg::GearReport::REVERSE: - gear_label_ptr_->setText("REVERSE"); - break; - case autoware_auto_vehicle_msgs::msg::GearReport::DRIVE: - gear_label_ptr_->setText("DRIVE"); - break; - case autoware_auto_vehicle_msgs::msg::GearReport::NEUTRAL: - gear_label_ptr_->setText("NEUTRAL"); - break; - case autoware_auto_vehicle_msgs::msg::GearReport::LOW: - gear_label_ptr_->setText("LOW"); - break; + mrm_behavior_icon->updateStyle(state, bgColor); + mrm_behavior_label_ptr_->setText(mrm_behavior); } } @@ -554,18 +745,37 @@ void AutowareStatePanel::onEmergencyStatus( { current_emergency_ = msg->emergency; if (msg->emergency) { - emergency_button_ptr_->setText(QString::fromStdString("Clear Emergency")); - emergency_button_ptr_->setStyleSheet("background-color: #FF0000;"); + emergency_button_ptr_->updateStyle( + "Clear Emergency", + QColor(autoware::state_rviz_plugin::colors::default_colors.error_container.c_str()), + QColor(autoware::state_rviz_plugin::colors::default_colors.on_error_container.c_str()), + QColor(autoware::state_rviz_plugin::colors::default_colors.on_error.c_str()), + QColor(autoware::state_rviz_plugin::colors::default_colors.on_error_container.c_str()), + QColor(autoware::state_rviz_plugin::colors::default_colors.error_container.c_str())); } else { - emergency_button_ptr_->setText(QString::fromStdString("Set Emergency")); - emergency_button_ptr_->setStyleSheet("background-color: #00FF00;"); + emergency_button_ptr_->updateStyle( + "Set Emergency", QColor(autoware::state_rviz_plugin::colors::default_colors.primary.c_str()), + QColor(autoware::state_rviz_plugin::colors::default_colors.on_primary.c_str()), + QColor(autoware::state_rviz_plugin::colors::default_colors.on_primary_container.c_str()), + QColor(autoware::state_rviz_plugin::colors::default_colors.on_primary.c_str()), + QColor(autoware::state_rviz_plugin::colors::default_colors.surface_tint.c_str())); + } +} + +void AutowareStatePanel::onSwitchStateChanged(int state) +{ + if (state == 0) { + // call the control mode function + onClickDirectControl(); + } else if (state == 2) { + onClickAutowareControl(); } } void AutowareStatePanel::onClickVelocityLimit() { auto velocity_limit = std::make_shared(); - velocity_limit->max_velocity = pub_velocity_limit_input_->value() / 3.6; + velocity_limit->max_velocity = velocity_limit_value_label_->text().toDouble() / 3.6; pub_velocity_limit_->publish(*velocity_limit); } diff --git a/common/tier4_state_rviz_plugin/src/custom_button.cpp b/common/tier4_state_rviz_plugin/src/custom_button.cpp new file mode 100644 index 0000000000000..0ef2628577135 --- /dev/null +++ b/common/tier4_state_rviz_plugin/src/custom_button.cpp @@ -0,0 +1,129 @@ +// 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 "include/custom_button.hpp" + +#include "src/include/material_colors.hpp" + +CustomElevatedButton::CustomElevatedButton( + const QString & text, const QColor & bgColor, const QColor & textColor, const QColor & hoverColor, + const QColor & disabledBgColor, const QColor & disabledTextColor, QWidget * parent) +: QPushButton(text, parent), + backgroundColor(bgColor), + textColor(textColor), + hoverColor(hoverColor), + disabledBgColor(disabledBgColor), + disabledTextColor(disabledTextColor) +{ + setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Fixed); + setCursor(Qt::PointingHandCursor); + + // set font weight to bold and size to 12 + QFont font = this->font(); + font.setWeight(QFont::Bold); + font.setFamily("Roboto"); + setFont(font); + + // Set up drop shadow effect + QGraphicsDropShadowEffect * shadowEffect = new QGraphicsDropShadowEffect(this); + shadowEffect->setBlurRadius(15); + shadowEffect->setOffset(3, 3); + shadowEffect->setColor( + QColor(autoware::state_rviz_plugin::colors::default_colors.shadow.c_str())); + setGraphicsEffect(shadowEffect); +} + +QSize CustomElevatedButton::sizeHint() const +{ + QFontMetrics fm(font()); + int textWidth = fm.horizontalAdvance(text()); + int textHeight = fm.height(); + int width = textWidth + 45; // Adding padding + int height = textHeight + 25; // Adding padding + return QSize(width, height); +} + +QSize CustomElevatedButton::minimumSizeHint() const +{ + return sizeHint(); +} + +void CustomElevatedButton::updateStyle( + const QString & text, const QColor & bgColor, const QColor & textColor, const QColor & hoverColor, + const QColor & disabledBgColor, const QColor & disabledTextColor) +{ + setText(text); + backgroundColor = bgColor; + this->textColor = textColor; + this->hoverColor = hoverColor; + this->disabledBgColor = disabledBgColor; + this->disabledTextColor = disabledTextColor; + update(); // Force repaint +} + +void CustomElevatedButton::paintEvent(QPaintEvent *) +{ + QPainter painter(this); + painter.setRenderHint(QPainter::Antialiasing); + + QStyleOption opt; + opt.initFrom(this); + QRect r = rect(); + + QColor buttonColor; + QColor currentTextColor = textColor; + if (!isEnabled()) { + buttonColor = disabledBgColor; + currentTextColor = disabledTextColor; + } else if (isHovered) { + buttonColor = hoverColor; + } else { + buttonColor = backgroundColor; + } + + int cornerRadius = height() / 2; // Making the corner radius proportional to the height + + // Draw button background + QPainterPath backgroundPath; + backgroundPath.addRoundedRect(r, cornerRadius, cornerRadius); + if (!isEnabled()) { + painter.setBrush( + QColor(autoware::state_rviz_plugin::colors::default_colors.on_surface.c_str())); + painter.setOpacity(0.12); + } else { + painter.setBrush(buttonColor); + } + painter.setPen(Qt::NoPen); + painter.drawPath(backgroundPath); + + // Draw button text + if (!isEnabled()) { + painter.setOpacity(0.38); + } + painter.setPen(currentTextColor); + painter.drawText(r, Qt::AlignCenter, text()); +} + +void CustomElevatedButton::enterEvent(QEvent * event) +{ + isHovered = true; + update(); + QPushButton::enterEvent(event); +} + +void CustomElevatedButton::leaveEvent(QEvent * event) +{ + isHovered = false; + update(); + QPushButton::leaveEvent(event); +} diff --git a/common/tier4_state_rviz_plugin/src/custom_container.cpp b/common/tier4_state_rviz_plugin/src/custom_container.cpp new file mode 100644 index 0000000000000..0b0aa1ccd6ed5 --- /dev/null +++ b/common/tier4_state_rviz_plugin/src/custom_container.cpp @@ -0,0 +1,70 @@ +// 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 "include/custom_container.hpp" + +#include "src/include/material_colors.hpp" + +CustomContainer::CustomContainer(QWidget * parent) : QFrame(parent), cornerRadius(15) +{ + setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred); + setContentsMargins(0, 0, 0, 0); + layout = new QGridLayout(this); + layout->setMargin(0); // Margin between the border and child widgets + layout->setSpacing(0); // Spacing between child widgets + layout->setContentsMargins(10, 0, 10, 0); // Margin between the border and the layout + setLayout(layout); +} + +void CustomContainer::setCornerRadius(int radius) +{ + cornerRadius = radius; + update(); +} + +int CustomContainer::getCornerRadius() const +{ + return cornerRadius; +} + +QGridLayout * CustomContainer::getLayout() const +{ + return layout; // Provide access to the layout +} + +QSize CustomContainer::sizeHint() const +{ + QSize size = layout->sizeHint(); + int width = size.width() + 20; // Adding padding + int height = size.height() + 20; // Adding padding + return QSize(width, height); +} + +QSize CustomContainer::minimumSizeHint() const +{ + return sizeHint(); +} + +void CustomContainer::paintEvent(QPaintEvent *) +{ + QPainter painter(this); + painter.setRenderHint(QPainter::Antialiasing); + + // Draw background + QPainterPath path; + path.addRoundedRect(rect(), height() / 2, height() / 2); // Use height for rounded corners + painter.setPen(Qt::NoPen); + painter.setBrush(QColor( + autoware::state_rviz_plugin::colors::default_colors.surface.c_str())); // Background color + painter.drawPath(path); +} diff --git a/common/tier4_state_rviz_plugin/src/custom_icon_label.cpp b/common/tier4_state_rviz_plugin/src/custom_icon_label.cpp new file mode 100644 index 0000000000000..6e4d32d40f7fb --- /dev/null +++ b/common/tier4_state_rviz_plugin/src/custom_icon_label.cpp @@ -0,0 +1,80 @@ +// 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 "include/custom_icon_label.hpp" + +#include + +CustomIconLabel::CustomIconLabel(const QColor & bgColor, QWidget * parent) +: QLabel(parent), backgroundColor(bgColor) +{ + loadIcons(); + setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Preferred); + setAlignment(Qt::AlignCenter); + setFixedSize(35, 35); +} + +void CustomIconLabel::loadIcons() +{ + std::string packagePath = ament_index_cpp::get_package_share_directory("tier4_state_rviz_plugin"); + + iconMap[Active] = QPixmap(QString::fromStdString(packagePath + "/icons/assets/active.png")); + iconMap[Pending] = QPixmap(QString::fromStdString(packagePath + "/icons/assets/pending.png")); + iconMap[Danger] = QPixmap(QString::fromStdString(packagePath + "/icons/assets/danger.png")); + iconMap[None] = QPixmap(QString::fromStdString(packagePath + "/icons/assets/none.png")); + iconMap[Crash] = QPixmap(QString::fromStdString(packagePath + "/icons/assets/crash.png")); + + icon = iconMap[None]; // Default icon +} + +void CustomIconLabel::updateStyle(IconState state, const QColor & bgColor) +{ + icon = iconMap[state]; + backgroundColor = bgColor; + update(); // Force repaint +} + +QSize CustomIconLabel::sizeHint() const +{ + int size = qMax(icon.width(), icon.height()) + 20; // Adding padding + return QSize(size, size); +} + +QSize CustomIconLabel::minimumSizeHint() const +{ + return sizeHint(); +} + +void CustomIconLabel::paintEvent(QPaintEvent *) +{ + QPainter painter(this); + painter.setRenderHint(QPainter::Antialiasing); + + int diameter = qMin(width(), height()); + int radius = diameter / 2; + + // Draw background circle + QPainterPath path; + path.addEllipse(width() / 2 - radius, height() / 2 - radius, diameter, diameter); + painter.setPen(Qt::NoPen); + painter.setBrush(backgroundColor); + painter.drawPath(path); + + // Draw icon in the center + if (!icon.isNull()) { + QSize iconSize = icon.size().scaled(diameter * 0.6, diameter * 0.6, Qt::KeepAspectRatio); + QPoint iconPos((width() - iconSize.width()) / 2, (height() - iconSize.height()) / 2); + painter.drawPixmap( + iconPos, icon.scaled(iconSize, Qt::KeepAspectRatio, Qt::SmoothTransformation)); + } +} diff --git a/common/tier4_state_rviz_plugin/src/custom_label.cpp b/common/tier4_state_rviz_plugin/src/custom_label.cpp new file mode 100644 index 0000000000000..1f96fc0d45095 --- /dev/null +++ b/common/tier4_state_rviz_plugin/src/custom_label.cpp @@ -0,0 +1,82 @@ +// 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 "include/custom_label.hpp" + +#include "src/include/material_colors.hpp" + +#include +#include +#include +#include +#include +#include + +CustomLabel::CustomLabel(const QString & text, QWidget * parent) : QLabel(text, parent) +{ + setFont(QFont("Roboto", 10, QFont::Bold)); // Set the font as needed + setAlignment(Qt::AlignCenter); + + // Add shadow effect + QGraphicsDropShadowEffect * shadowEffect = new QGraphicsDropShadowEffect(this); + shadowEffect->setBlurRadius(15); // Blur radius for a smoother shadow + shadowEffect->setOffset(3, 3); // Offset for the shadow + shadowEffect->setColor( + QColor(autoware::state_rviz_plugin::colors::default_colors.shadow.c_str())); // Shadow color + setGraphicsEffect(shadowEffect); +} + +QSize CustomLabel::sizeHint() const +{ + QFontMetrics fm(font()); + int textWidth = fm.horizontalAdvance(text()); + int textHeight = fm.height(); + int width = textWidth + 40; // Adding padding + int height = textHeight; // Adding padding + return QSize(width, height); +} + +QSize CustomLabel::minimumSizeHint() const +{ + return sizeHint(); +} + +void CustomLabel::paintEvent(QPaintEvent *) +{ + QPainter painter(this); + painter.setRenderHint(QPainter::Antialiasing); + + int cornerRadius = height() / 2; // Making the corner radius proportional to the height + + // Draw background + QPainterPath path; + path.addRoundedRect(rect().adjusted(1, 1, -1, -1), cornerRadius, cornerRadius); + + painter.setPen(Qt::NoPen); + painter.setBrush(backgroundColor); + + painter.drawPath(path); + + // Set text color and draw text + painter.setPen(textColor); + painter.drawText(rect(), Qt::AlignCenter, text()); +} + +void CustomLabel::updateStyle( + const QString & text, const QColor & bg_color, const QColor & text_color) +{ + setText(text); + backgroundColor = bg_color; + textColor = text_color; + update(); // Force repaint +} diff --git a/common/tier4_state_rviz_plugin/src/custom_segmented_button.cpp b/common/tier4_state_rviz_plugin/src/custom_segmented_button.cpp new file mode 100644 index 0000000000000..8063bdc0fbc28 --- /dev/null +++ b/common/tier4_state_rviz_plugin/src/custom_segmented_button.cpp @@ -0,0 +1,75 @@ +// 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 "include/custom_segmented_button.hpp" + +#include + +CustomSegmentedButton::CustomSegmentedButton(QWidget * parent) +: QWidget(parent), buttonGroup(new QButtonGroup(this)), layout(new QHBoxLayout(this)) +{ + setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed); + layout->setContentsMargins(0, 0, 0, 0); // Ensure no margins around the layout + layout->setSpacing(0); // Ensure no spacing between buttons + + setLayout(layout); + + buttonGroup->setExclusive(true); + + connect( + buttonGroup, QOverload::of(&QButtonGroup::idClicked), this, + &CustomSegmentedButton::buttonClicked); +} + +CustomSegmentedButtonItem * CustomSegmentedButton::addButton(const QString & text) +{ + CustomSegmentedButtonItem * button = new CustomSegmentedButtonItem(text); + layout->addWidget(button); + buttonGroup->addButton(button, layout->count() - 1); + + return button; +} + +QButtonGroup * CustomSegmentedButton::getButtonGroup() const +{ + return buttonGroup; +} + +QSize CustomSegmentedButton::sizeHint() const +{ + return QSize(400, 40); // Adjust the size hint as needed + + // return QSize( + // layout->count() * (layout->itemAt(0)->widget()->width()), + // layout->itemAt(0)->widget()->height() + 10); +} + +QSize CustomSegmentedButton::minimumSizeHint() const +{ + return sizeHint(); +} + +void CustomSegmentedButton::paintEvent(QPaintEvent *) +{ + QPainter painter(this); + painter.setRenderHint(QPainter::Antialiasing); + + // Draw background + QPainterPath path; + path.addRoundedRect(rect(), height() / 2, height() / 2); + + painter.setPen(Qt::NoPen); + painter.setBrush( + QColor(autoware::state_rviz_plugin::colors::default_colors.surface_container_low.c_str())); + painter.drawPath(path); +} diff --git a/common/tier4_state_rviz_plugin/src/custom_segmented_button_item.cpp b/common/tier4_state_rviz_plugin/src/custom_segmented_button_item.cpp new file mode 100644 index 0000000000000..f2d15260c4e41 --- /dev/null +++ b/common/tier4_state_rviz_plugin/src/custom_segmented_button_item.cpp @@ -0,0 +1,186 @@ +// 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 "include/custom_segmented_button_item.hpp" + +CustomSegmentedButtonItem::CustomSegmentedButtonItem(const QString & text, QWidget * parent) +: QPushButton(text, parent), + bgColor( + QColor(autoware::state_rviz_plugin::colors::default_colors.surface_container_low.c_str())), + checkedBgColor( + QColor(autoware::state_rviz_plugin::colors::default_colors.secondary_container.c_str())), + inactiveTextColor(QColor(autoware::state_rviz_plugin::colors::default_colors.on_surface.c_str())), + activeTextColor( + QColor(autoware::state_rviz_plugin::colors::default_colors.on_secondary_container.c_str())), + isHovered(false), + isActivated(false), + isDisabled(false) + +{ + setCheckable(true); + setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred); + setCursor(Qt::PointingHandCursor); +} + +void CustomSegmentedButtonItem::setColors( + const QColor & bg, const QColor & checkedBg, const QColor & activeText, + const QColor & inactiveText) +{ + bgColor = bg; + checkedBgColor = checkedBg; + activeTextColor = activeText; + inactiveTextColor = inactiveText; + update(); +} + +// void CustomSegmentedButtonItem::updateSize() +// { +// QFontMetrics fm(font()); +// int width = fm.horizontalAdvance(text()) + 40; // Add padding +// int height = fm.height() + 20; // Add padding +// setFixedSize(width, height); +// } + +void CustomSegmentedButtonItem::setHovered(bool hovered) +{ + isHovered = hovered; + updateCheckableState(); +} + +void CustomSegmentedButtonItem::setCheckableButton(bool checkable) +{ + setCheckable(checkable); + updateCheckableState(); +} + +void CustomSegmentedButtonItem::updateCheckableState() +{ + setCursor( + isDisabled ? Qt::ForbiddenCursor + : (isCheckable() ? Qt::PointingHandCursor : Qt::ForbiddenCursor)); + update(); +} + +void CustomSegmentedButtonItem::setDisabledButton(bool disabled) +{ + isDisabled = disabled; + updateCheckableState(); +} + +void CustomSegmentedButtonItem::setActivated(bool activated) +{ + isActivated = activated; + update(); +} + +void CustomSegmentedButtonItem::paintEvent(QPaintEvent *) +{ + QPainter painter(this); + painter.setRenderHint(QPainter::Antialiasing); + + // Adjust opacity for disabled state + if (isDisabled) { + painter.setOpacity(0.3); + } else { + painter.setOpacity(1.0); + } + + // Determine the button's color based on its state + QColor buttonColor; + if (isDisabled) { + buttonColor = disabledBgColor; + } else if (isHovered && !isChecked() && isCheckable()) { + buttonColor = hoverColor; + } else if (isActivated) { + buttonColor = checkedBgColor; + } else { + buttonColor = isChecked() ? checkedBgColor : bgColor; + } + + // Determine if this is the first or last button + bool isFirstButton = false; + bool isLastButton = false; + + QHBoxLayout * parentLayout = qobject_cast(parentWidget()->layout()); + if (parentLayout) { + int index = parentLayout->indexOf(this); + isFirstButton = (index == 0); + isLastButton = (index == parentLayout->count() - 1); + } + + // Draw button background + + QRect buttonRect = rect().adjusted(0, 1, 0, -1); + + if (isFirstButton) { + buttonRect.setLeft(buttonRect.left() + 1); + } + if (isLastButton) { + buttonRect.setRight(buttonRect.right() - 1); + } + + QPainterPath path; + double radius = (height() - 2) / 2; + + path.setFillRule(Qt::WindingFill); + if (isFirstButton) { + path.addRoundedRect(buttonRect, radius, radius); + path.addRect(QRect( + (buttonRect.left() + buttonRect.width() - radius), + buttonRect.top() + buttonRect.height() - radius, radius, + radius)); // Bottom Right + path.addRect(QRect( + (buttonRect.left() + buttonRect.width() - radius), buttonRect.top(), radius, + radius)); // Top Right + } else if (isLastButton) { + path.addRoundedRect(buttonRect, radius, radius); + path.addRect(QRect( + (buttonRect.left()), buttonRect.top() + buttonRect.height() - radius, radius, + radius)); // Bottom left + path.addRect(QRect((buttonRect.left()), buttonRect.top(), radius, + radius)); // Top Left + } else { + path.addRect(buttonRect); + } + painter.fillPath(path, buttonColor); + + // Draw button border + QPen pen(QColor(autoware::state_rviz_plugin::colors::default_colors.outline.c_str()), 1); + pen.setJoinStyle(Qt::RoundJoin); + pen.setCapStyle(Qt::RoundCap); + painter.setPen(pen); + painter.drawPath(path.simplified()); + + // Draw button text + QColor textColor = (isChecked() ? activeTextColor : inactiveTextColor); + painter.setPen(textColor); + painter.drawText(rect(), Qt::AlignCenter, text()); +} + +void CustomSegmentedButtonItem::enterEvent(QEvent * event) +{ + if (isCheckable()) { + isHovered = true; + update(); + } + QPushButton::enterEvent(event); +} + +void CustomSegmentedButtonItem::leaveEvent(QEvent * event) +{ + if (isCheckable()) { + isHovered = false; + update(); + } + QPushButton::leaveEvent(event); +} diff --git a/common/tier4_state_rviz_plugin/src/custom_slider.cpp b/common/tier4_state_rviz_plugin/src/custom_slider.cpp new file mode 100644 index 0000000000000..cf3f7c3d4638f --- /dev/null +++ b/common/tier4_state_rviz_plugin/src/custom_slider.cpp @@ -0,0 +1,102 @@ +// 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 "include/custom_slider.hpp" + +CustomSlider::CustomSlider(Qt::Orientation orientation, QWidget * parent) +: QSlider(orientation, parent) +{ + setMinimumHeight(40); // Ensure there's enough space for the custom track +} + +void CustomSlider::paintEvent(QPaintEvent *) +{ + QPainter painter(this); + painter.setRenderHint(QPainter::Antialiasing); + painter.setPen(Qt::NoPen); + + // Initialize style option + QStyleOptionSlider opt; + initStyleOption(&opt); + + QRect grooveRect = + style()->subControlRect(QStyle::CC_Slider, &opt, QStyle::SC_SliderGroove, this); + int centerY = grooveRect.center().y(); + QRect handleRect = + style()->subControlRect(QStyle::CC_Slider, &opt, QStyle::SC_SliderHandle, this); + + int value = this->value(); + int minValue = this->minimum(); + int maxValue = this->maximum(); + + int trackThickness = 14; + int gap = 8; + + QRect beforeRect( + grooveRect.x(), centerY - trackThickness / 2, handleRect.center().x() - grooveRect.x() - gap, + trackThickness); + + QRect afterRect( + handleRect.center().x() + gap, centerY - trackThickness / 2, + grooveRect.right() - handleRect.center().x() - gap, trackThickness); + + QColor inactiveTrackColor( + autoware::state_rviz_plugin::colors::default_colors.primary_container.c_str()); + QColor activeTrackColor(autoware::state_rviz_plugin::colors::default_colors.primary.c_str()); + QColor handleColor(autoware::state_rviz_plugin::colors::default_colors.primary.c_str()); + + // only draw the active track if the value is more than the gap from the minimum + if (value > minValue + gap / 2) { + QPainterPath beforePath; + beforePath.moveTo(beforeRect.left(), centerY + trackThickness / 2); // Start from bottom-left + beforePath.quadTo( + beforeRect.left(), centerY - trackThickness / 2, beforeRect.left() + trackThickness * 0.5, + centerY - trackThickness / 2); + beforePath.lineTo(beforeRect.right() - trackThickness * 0.1, centerY - trackThickness / 2); + beforePath.quadTo( + beforeRect.right(), centerY - trackThickness / 2, beforeRect.right(), centerY); + beforePath.quadTo( + beforeRect.right(), centerY + trackThickness / 2, beforeRect.right() - trackThickness * 0.1, + centerY + trackThickness / 2); + beforePath.lineTo(beforeRect.left() + trackThickness * 0.5, centerY + trackThickness / 2); + beforePath.quadTo(beforeRect.left(), centerY + trackThickness / 2, beforeRect.left(), centerY); + painter.fillPath(beforePath, activeTrackColor); + } + + if (value < maxValue - gap / 2) { + QPainterPath afterPath; + afterPath.moveTo(afterRect.left(), centerY + trackThickness / 2); + afterPath.quadTo( + afterRect.left(), centerY - trackThickness / 2, afterRect.left() + trackThickness * 0.1, + centerY - trackThickness / 2); + afterPath.lineTo(afterRect.right() - trackThickness * 0.5, centerY - trackThickness / 2); + afterPath.quadTo(afterRect.right(), centerY - trackThickness / 2, afterRect.right(), centerY); + afterPath.quadTo( + afterRect.right(), centerY + trackThickness / 2, afterRect.right() - trackThickness * 0.5, + centerY + trackThickness / 2); + afterPath.lineTo(afterRect.left() + trackThickness * 0.1, centerY + trackThickness / 2); + afterPath.quadTo(afterRect.left(), centerY + trackThickness / 2, afterRect.left(), centerY); + painter.fillPath(afterPath, inactiveTrackColor); + } + + painter.setBrush(handleColor); + int handleLineHeight = 30; + int handleLineWidth = 4; + int handleLineRadius = 2; + QRect handleLineRect( + handleRect.center().x() - handleLineWidth / 2, centerY - handleLineHeight / 2, handleLineWidth, + handleLineHeight); + QPainterPath handlePath; + handlePath.addRoundedRect(handleLineRect, handleLineRadius, handleLineRadius); + painter.fillPath(handlePath, handleColor); +} diff --git a/common/tier4_state_rviz_plugin/src/custom_toggle_switch.cpp b/common/tier4_state_rviz_plugin/src/custom_toggle_switch.cpp new file mode 100644 index 0000000000000..3b58ded626439 --- /dev/null +++ b/common/tier4_state_rviz_plugin/src/custom_toggle_switch.cpp @@ -0,0 +1,87 @@ +// 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 "include/custom_toggle_switch.hpp" + +CustomToggleSwitch::CustomToggleSwitch(QWidget * parent) : QCheckBox(parent) +{ + setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed); + setCursor(Qt::PointingHandCursor); + + connect(this, &QCheckBox::stateChanged, this, [this]() { + if (!blockSignalsGuard) { + update(); // Force repaint + } + }); +} + +QSize CustomToggleSwitch::sizeHint() const +{ + return QSize(50, 30); // Preferred size of the toggle switch +} + +void CustomToggleSwitch::paintEvent(QPaintEvent *) +{ + QPainter p(this); + p.setRenderHint(QPainter::Antialiasing); + + int margin = 2; + int circleRadius = height() / 2 - margin * 2; + QRect r = rect().adjusted(margin, margin, -margin, -margin); + bool isChecked = this->isChecked(); + + QColor uncheckedIndicatorColor = + QColor(autoware::state_rviz_plugin::colors::default_colors.outline.c_str()); + QColor checkedIndicatorColor = + QColor(autoware::state_rviz_plugin::colors::default_colors.on_primary.c_str()); + QColor indicatorColor = isChecked ? checkedIndicatorColor : uncheckedIndicatorColor; + + QColor uncheckedBgColor = + QColor(autoware::state_rviz_plugin::colors::default_colors.surface_container_highest.c_str()); + QColor checkedBgColor = + QColor(autoware::state_rviz_plugin::colors::default_colors.primary.c_str()); + + QColor bgColor = isChecked ? checkedBgColor : uncheckedBgColor; + + QRect borderR = r.adjusted(-margin, -margin, margin, margin); + p.setBrush(bgColor); + p.setPen(Qt::NoPen); + p.drawRoundedRect(borderR, circleRadius + 4, circleRadius + 4); + + p.setBrush(bgColor); + p.setPen(Qt::NoPen); + p.drawRoundedRect(r, circleRadius + 4, circleRadius + 4); + + int minX = r.left() + margin * 2; + int maxX = r.right() - circleRadius * 2 - margin; + int circleX = isChecked ? maxX : minX; + QRect circleRect(circleX, r.top() + margin, circleRadius * 2, circleRadius * 2); + p.setBrush(indicatorColor); + p.drawEllipse(circleRect); +} + +void CustomToggleSwitch::mouseReleaseEvent(QMouseEvent * event) +{ + if (event->button() == Qt::LeftButton) { + setCheckedState(!isChecked()); + } + QCheckBox::mouseReleaseEvent(event); +} + +void CustomToggleSwitch::setCheckedState(bool state) +{ + blockSignalsGuard = true; + setChecked(state); + blockSignalsGuard = false; + update(); // Force repaint +} diff --git a/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp b/common/tier4_state_rviz_plugin/src/include/autoware_state_panel.hpp similarity index 72% rename from common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp rename to common/tier4_state_rviz_plugin/src/include/autoware_state_panel.hpp index 8f67a90215bd1..9863cbbbf802b 100644 --- a/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp +++ b/common/tier4_state_rviz_plugin/src/include/autoware_state_panel.hpp @@ -17,12 +17,26 @@ #ifndef AUTOWARE_STATE_PANEL_HPP_ #define AUTOWARE_STATE_PANEL_HPP_ -#include +#include "custom_button.hpp" +#include "custom_container.hpp" +#include "custom_icon_label.hpp" +#include "custom_label.hpp" +#include "custom_segmented_button.hpp" +#include "custom_segmented_button_item.hpp" +#include "custom_slider.hpp" +#include "custom_toggle_switch.hpp" +#include "material_colors.hpp" + +#include +#include +#include #include -#include #include +#include #include -#include +#include +#include +#include #include #include @@ -36,11 +50,17 @@ #include #include #include +#include +#include #include #include #include +#include + #include +#include +#include namespace rviz_plugins { @@ -56,6 +76,8 @@ class AutowareStatePanel : public rviz_common::Panel using MotionState = autoware_adapi_v1_msgs::msg::MotionState; using AcceptStart = autoware_adapi_v1_msgs::srv::AcceptStart; using MRMState = autoware_adapi_v1_msgs::msg::MrmState; + using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray; + using DiagnosticStatus = diagnostic_msgs::msg::DiagnosticStatus; Q_OBJECT @@ -75,17 +97,19 @@ public Q_SLOTS: // NOLINT for Qt void onClickAcceptStart(); void onClickVelocityLimit(); void onClickEmergencyButton(); + void onSwitchStateChanged(int state); protected: // Layout - QGroupBox * makeOperationModeGroup(); - QGroupBox * makeControlModeGroup(); - QGroupBox * makeRoutingGroup(); - QGroupBox * makeLocalizationGroup(); - QGroupBox * makeMotionGroup(); - QGroupBox * makeFailSafeGroup(); - - void onShift(const autoware_auto_vehicle_msgs::msg::GearReport::ConstSharedPtr msg); + QVBoxLayout * makeVelocityLimitGroup(); + QVBoxLayout * makeOperationModeGroup(); + QVBoxLayout * makeRoutingGroup(); + QVBoxLayout * makeLocalizationGroup(); + QVBoxLayout * makeMotionGroup(); + QVBoxLayout * makeFailSafeGroup(); + // QVBoxLayout * makeDiagnosticGroup(); + + // void onShift(const autoware_auto_vehicle_msgs::msg::GearReport::ConstSharedPtr msg); void onEmergencyStatus(const tier4_external_api_msgs::msg::Emergency::ConstSharedPtr msg); rclcpp::Node::SharedPtr raw_node_; @@ -97,13 +121,15 @@ public Q_SLOTS: // NOLINT for Qt rclcpp::Publisher::SharedPtr pub_velocity_limit_; + QLabel * velocity_limit_value_label_{nullptr}; + bool sliderIsDragging = false; + // Operation Mode - //// Gate Mode QLabel * operation_mode_label_ptr_{nullptr}; - QPushButton * stop_button_ptr_{nullptr}; - QPushButton * auto_button_ptr_{nullptr}; - QPushButton * local_button_ptr_{nullptr}; - QPushButton * remote_button_ptr_{nullptr}; + CustomSegmentedButtonItem * stop_button_ptr_{nullptr}; + CustomSegmentedButtonItem * auto_button_ptr_{nullptr}; + CustomSegmentedButtonItem * local_button_ptr_{nullptr}; + CustomSegmentedButtonItem * remote_button_ptr_{nullptr}; rclcpp::Subscription::SharedPtr sub_operation_mode_; rclcpp::Client::SharedPtr client_change_to_autonomous_; @@ -112,6 +138,8 @@ public Q_SLOTS: // NOLINT for Qt rclcpp::Client::SharedPtr client_change_to_remote_; //// Control Mode + CustomSegmentedButton * segmented_button; + CustomToggleSwitch * control_mode_switch_ptr_{nullptr}; QLabel * control_mode_label_ptr_{nullptr}; QPushButton * enable_button_ptr_{nullptr}; QPushButton * disable_button_ptr_{nullptr}; @@ -123,8 +151,9 @@ public Q_SLOTS: // NOLINT for Qt void changeOperationMode(const rclcpp::Client::SharedPtr client); // Routing + CustomIconLabel * routing_icon{nullptr}; + CustomElevatedButton * clear_route_button_ptr_{nullptr}; QLabel * routing_label_ptr_{nullptr}; - QPushButton * clear_route_button_ptr_{nullptr}; rclcpp::Subscription::SharedPtr sub_route_; rclcpp::Client::SharedPtr client_clear_route_; @@ -132,8 +161,9 @@ public Q_SLOTS: // NOLINT for Qt void onRoute(const RouteState::ConstSharedPtr msg); // Localization + CustomIconLabel * localization_icon{nullptr}; + CustomElevatedButton * init_by_gnss_button_ptr_{nullptr}; QLabel * localization_label_ptr_{nullptr}; - QPushButton * init_by_gnss_button_ptr_{nullptr}; rclcpp::Subscription::SharedPtr sub_localization_; rclcpp::Client::SharedPtr client_init_by_gnss_; @@ -141,8 +171,9 @@ public Q_SLOTS: // NOLINT for Qt void onLocalization(const LocalizationInitializationState::ConstSharedPtr msg); // Motion + CustomIconLabel * motion_icon{nullptr}; + CustomElevatedButton * accept_start_button_ptr_{nullptr}; QLabel * motion_label_ptr_{nullptr}; - QPushButton * accept_start_button_ptr_{nullptr}; rclcpp::Subscription::SharedPtr sub_motion_; rclcpp::Client::SharedPtr client_accept_start_; @@ -150,7 +181,9 @@ public Q_SLOTS: // NOLINT for Qt void onMotion(const MotionState::ConstSharedPtr msg); // FailSafe + CustomIconLabel * mrm_state_icon{nullptr}; QLabel * mrm_state_label_ptr_{nullptr}; + CustomIconLabel * mrm_behavior_icon{nullptr}; QLabel * mrm_behavior_label_ptr_{nullptr}; rclcpp::Subscription::SharedPtr sub_mrm_; @@ -158,11 +191,11 @@ public Q_SLOTS: // NOLINT for Qt void onMRMState(const MRMState::ConstSharedPtr msg); // Others - QPushButton * velocity_limit_button_ptr_; + QLabel * velocity_limit_setter_ptr_; QLabel * gear_label_ptr_; QSpinBox * pub_velocity_limit_input_; - QPushButton * emergency_button_ptr_; + CustomElevatedButton * emergency_button_ptr_; bool current_emergency_{false}; @@ -190,6 +223,17 @@ public Q_SLOTS: // NOLINT for Qt label->setText(text); label->setStyleSheet(style_sheet); } + static void updateCustomLabel( + CustomLabel * label, QString text, QColor bg_color, QColor text_color) + { + label->updateStyle(text, bg_color, text_color); + } + + static void updateButton(QPushButton * button, QString text, QString style_sheet) + { + button->setText(text); + button->setStyleSheet(style_sheet); + } static void activateButton(QAbstractButton * button) { diff --git a/common/tier4_state_rviz_plugin/src/include/custom_button.hpp b/common/tier4_state_rviz_plugin/src/include/custom_button.hpp new file mode 100644 index 0000000000000..b10663ce09933 --- /dev/null +++ b/common/tier4_state_rviz_plugin/src/include/custom_button.hpp @@ -0,0 +1,69 @@ +// 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 CUSTOM_BUTTON_HPP_ +#define CUSTOM_BUTTON_HPP_ + +#include "material_colors.hpp" + +#include +#include +#include +#include +#include +#include +#include + +class CustomElevatedButton : public QPushButton +{ + Q_OBJECT + +public: + explicit CustomElevatedButton( + const QString & text, + const QColor & bgColor = + QColor(autoware::state_rviz_plugin::colors::default_colors.surface_container_low.c_str()), + const QColor & textColor = + QColor(autoware::state_rviz_plugin::colors::default_colors.primary.c_str()), + const QColor & hoverColor = + QColor(autoware::state_rviz_plugin::colors::default_colors.surface_container_highest.c_str()), + const QColor & disabledBgColor = + QColor(autoware::state_rviz_plugin::colors::default_colors.surface_container_high.c_str()), + const QColor & disabledTextColor = + QColor(autoware::state_rviz_plugin::colors::default_colors.on_surface_variant.c_str()), + QWidget * parent = nullptr); + void updateStyle( + const QString & text, const QColor & bgColor, const QColor & textColor, + const QColor & hoverColor, const QColor & disabledBgColor, const QColor & disabledTextColor); + +protected: + void paintEvent(QPaintEvent * event) override; + void enterEvent(QEvent * event) override; + void leaveEvent(QEvent * event) override; + QSize sizeHint() const override; + QSize minimumSizeHint() const override; + +private: + QColor backgroundColor = + QColor(autoware::state_rviz_plugin::colors::default_colors.surface_container_low.c_str()); + QColor textColor = QColor(autoware::state_rviz_plugin::colors::default_colors.primary.c_str()); + QColor hoverColor = + QColor(autoware::state_rviz_plugin::colors::default_colors.surface_container_highest.c_str()); + QColor disabledBgColor = + QColor(autoware::state_rviz_plugin::colors::default_colors.disabled_elevated_button_bg.c_str()); + QColor disabledTextColor = + QColor(autoware::state_rviz_plugin::colors::default_colors.on_surface.c_str()); + bool isHovered = false; +}; + +#endif // CUSTOM_BUTTON_HPP_ diff --git a/common/tier4_state_rviz_plugin/src/include/custom_container.hpp b/common/tier4_state_rviz_plugin/src/include/custom_container.hpp new file mode 100644 index 0000000000000..5142b409ebc88 --- /dev/null +++ b/common/tier4_state_rviz_plugin/src/include/custom_container.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 CUSTOM_CONTAINER_HPP_ +#define CUSTOM_CONTAINER_HPP_ + +#include "material_colors.hpp" + +#include +#include +#include +#include + +class CustomContainer : public QFrame +{ + Q_OBJECT + +public: + explicit CustomContainer(QWidget * parent = nullptr); + + // Methods to set dimensions and corner radius + void setContainerHeight(int height); + void setContainerWidth(int width); + void setCornerRadius(int radius); + + // Getters + int getContainerHeight() const; + int getContainerWidth() const; + int getCornerRadius() const; + QGridLayout * getLayout() const; // Add a method to access the layout + +protected: + void paintEvent(QPaintEvent * event) override; + QSize sizeHint() const override; + QSize minimumSizeHint() const override; + +private: + QGridLayout * layout; + int cornerRadius; +}; + +#endif // CUSTOM_CONTAINER_HPP_ diff --git a/common/tier4_state_rviz_plugin/src/include/custom_icon_label.hpp b/common/tier4_state_rviz_plugin/src/include/custom_icon_label.hpp new file mode 100644 index 0000000000000..1b3ab9c8e0c6c --- /dev/null +++ b/common/tier4_state_rviz_plugin/src/include/custom_icon_label.hpp @@ -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. +#ifndef CUSTOM_ICON_LABEL_HPP_ +#define CUSTOM_ICON_LABEL_HPP_ + +#include "material_colors.hpp" + +#include +#include +#include +#include +#include +#include +#include +#include + +enum IconState { Active, Pending, Danger, None, Crash }; + +class CustomIconLabel : public QLabel +{ + Q_OBJECT + +public: + explicit CustomIconLabel( + const QColor & bgColor = + QColor(autoware::state_rviz_plugin::colors::default_colors.surface_container_high.c_str()), + QWidget * parent = nullptr); + void updateStyle(IconState state, const QColor & bgColor); + +protected: + void paintEvent(QPaintEvent * event) override; + QSize sizeHint() const override; + QSize minimumSizeHint() const override; + +private: + void loadIcons(); + QPixmap icon; + QColor backgroundColor = + QColor(autoware::state_rviz_plugin::colors::default_colors.surface_container_high.c_str()); + QMap iconMap; +}; + +#endif // CUSTOM_ICON_LABEL_HPP_ diff --git a/common/tier4_state_rviz_plugin/src/include/custom_label.hpp b/common/tier4_state_rviz_plugin/src/include/custom_label.hpp new file mode 100644 index 0000000000000..a328c4de56e3d --- /dev/null +++ b/common/tier4_state_rviz_plugin/src/include/custom_label.hpp @@ -0,0 +1,46 @@ +// 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 CUSTOM_LABEL_HPP_ +#define CUSTOM_LABEL_HPP_ + +#include "material_colors.hpp" + +#include +#include +#include +class CustomLabel : public QLabel +{ + Q_OBJECT + +public: + explicit CustomLabel(const QString & text, QWidget * parent = nullptr); + void updateStyle( + const QString & text, + const QColor & bgColor = + QColor(autoware::state_rviz_plugin::colors::default_colors.surface_container_low.c_str()), + const QColor & textColor = + QColor(autoware::state_rviz_plugin::colors::default_colors.on_surface.c_str())); + +protected: + void paintEvent(QPaintEvent * event) override; + QSize sizeHint() const override; + QSize minimumSizeHint() const override; + +private: + QColor backgroundColor = + QColor(autoware::state_rviz_plugin::colors::default_colors.surface_container_low.c_str()); + QColor textColor = QColor(autoware::state_rviz_plugin::colors::default_colors.on_surface.c_str()); +}; + +#endif // CUSTOM_LABEL_HPP_ diff --git a/common/tier4_state_rviz_plugin/src/include/custom_segmented_button.hpp b/common/tier4_state_rviz_plugin/src/include/custom_segmented_button.hpp new file mode 100644 index 0000000000000..c6c589d31b8d4 --- /dev/null +++ b/common/tier4_state_rviz_plugin/src/include/custom_segmented_button.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 CUSTOM_SEGMENTED_BUTTON_HPP_ +#define CUSTOM_SEGMENTED_BUTTON_HPP_ + +#include "custom_segmented_button_item.hpp" +#include "material_colors.hpp" + +#include +#include +#include +#include +#include +#include +#include +#include + +class CustomSegmentedButton : public QWidget +{ + Q_OBJECT + +public: + explicit CustomSegmentedButton(QWidget * parent = nullptr); + + CustomSegmentedButtonItem * addButton(const QString & text); + QButtonGroup * getButtonGroup() const; + + QSize sizeHint() const override; + QSize minimumSizeHint() const override; + +Q_SIGNALS: + void buttonClicked(int id); + +protected: + void paintEvent(QPaintEvent * event) override; + +private: + QButtonGroup * buttonGroup; + QHBoxLayout * layout; +}; + +#endif // CUSTOM_SEGMENTED_BUTTON_HPP_ diff --git a/common/tier4_state_rviz_plugin/src/include/custom_segmented_button_item.hpp b/common/tier4_state_rviz_plugin/src/include/custom_segmented_button_item.hpp new file mode 100644 index 0000000000000..33eb9fe16aa31 --- /dev/null +++ b/common/tier4_state_rviz_plugin/src/include/custom_segmented_button_item.hpp @@ -0,0 +1,64 @@ +// 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 CUSTOM_SEGMENTED_BUTTON_ITEM_HPP_ +#define CUSTOM_SEGMENTED_BUTTON_ITEM_HPP_ + +#include "material_colors.hpp" + +#include +#include +#include +#include +#include +#include + +class CustomSegmentedButtonItem : public QPushButton +{ + Q_OBJECT + +public: + explicit CustomSegmentedButtonItem(const QString & text, QWidget * parent = nullptr); + + void setColors( + const QColor & bg, const QColor & checkedBg, const QColor & activeText, + const QColor & inactiveText); + void setActivated(bool activated); + void setCheckableButton(bool checkable); + void setDisabledButton(bool disabled); + void setHovered(bool hovered); + +protected: + void paintEvent(QPaintEvent * event) override; + void enterEvent(QEvent * event) override; + void leaveEvent(QEvent * event) override; + +private: + void updateCheckableState(); + + QColor bgColor; + QColor checkedBgColor; + QColor hoverColor = + QColor(autoware::state_rviz_plugin::colors::default_colors.surface_container_highest.c_str()); + QColor inactiveTextColor; + QColor activeTextColor; + QColor disabledBgColor = + QColor(autoware::state_rviz_plugin::colors::default_colors.surface_dim.c_str()); + QColor disabledTextColor = + QColor(autoware::state_rviz_plugin::colors::default_colors.on_surface_variant.c_str()); + bool isHovered = false; + bool isActivated = false; + bool isDisabled = false; +}; + +#endif // CUSTOM_SEGMENTED_BUTTON_ITEM_HPP_ diff --git a/common/mission_planner_rviz_plugin/src/mrm_goal.hpp b/common/tier4_state_rviz_plugin/src/include/custom_slider.hpp similarity index 60% rename from common/mission_planner_rviz_plugin/src/mrm_goal.hpp rename to common/tier4_state_rviz_plugin/src/include/custom_slider.hpp index e16b0abf0bab3..f0dc9f12aedfe 100644 --- a/common/mission_planner_rviz_plugin/src/mrm_goal.hpp +++ b/common/tier4_state_rviz_plugin/src/include/custom_slider.hpp @@ -11,24 +11,25 @@ // 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 CUSTOM_SLIDER_HPP_ +#define CUSTOM_SLIDER_HPP_ +#include "material_colors.hpp" -#ifndef MRM_GOAL_HPP_ -#define MRM_GOAL_HPP_ +#include +#include +#include +#include +#include -#include - -namespace rviz_plugins -{ - -class MrmGoalTool : public rviz_default_plugins::tools::GoalTool +class CustomSlider : public QSlider { Q_OBJECT public: - MrmGoalTool(); - void onInitialize() override; -}; + explicit CustomSlider(Qt::Orientation orientation, QWidget * parent = nullptr); -} // namespace rviz_plugins +protected: + void paintEvent(QPaintEvent * event) override; +}; -#endif // MRM_GOAL_HPP_ +#endif // CUSTOM_SLIDER_HPP_ diff --git a/common/tier4_state_rviz_plugin/src/include/custom_toggle_switch.hpp b/common/tier4_state_rviz_plugin/src/include/custom_toggle_switch.hpp new file mode 100644 index 0000000000000..107d45af8c3f3 --- /dev/null +++ b/common/tier4_state_rviz_plugin/src/include/custom_toggle_switch.hpp @@ -0,0 +1,40 @@ +// 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 CUSTOM_TOGGLE_SWITCH_HPP_ +#define CUSTOM_TOGGLE_SWITCH_HPP_ + +#include "material_colors.hpp" + +#include +#include +#include +#include +class CustomToggleSwitch : public QCheckBox +{ + Q_OBJECT + +public: + explicit CustomToggleSwitch(QWidget * parent = nullptr); + QSize sizeHint() const override; + void setCheckedState(bool state); + +protected: + void paintEvent(QPaintEvent * event) override; + void mouseReleaseEvent(QMouseEvent * event) override; + +private: + bool blockSignalsGuard = false; // Guard variable to block signals during updates +}; + +#endif // CUSTOM_TOGGLE_SWITCH_HPP_ diff --git a/common/tier4_state_rviz_plugin/src/include/material_colors.hpp b/common/tier4_state_rviz_plugin/src/include/material_colors.hpp new file mode 100644 index 0000000000000..d146b599ab600 --- /dev/null +++ b/common/tier4_state_rviz_plugin/src/include/material_colors.hpp @@ -0,0 +1,88 @@ +// 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 MATERIAL_COLORS_HPP_ +#define MATERIAL_COLORS_HPP_ +#include + +namespace autoware +{ +namespace state_rviz_plugin +{ +namespace colors +{ +struct MaterialColors +{ + std::string primary = "#8BD0F0"; + std::string surface_tint = "#8BD0F0"; + std::string on_primary = "#003546"; + std::string primary_container = "#004D64"; + std::string on_primary_container = "#BEE9FF"; + std::string secondary = "#B4CAD6"; + std::string on_secondary = "#1F333C"; + std::string secondary_container = "#354A54"; + std::string on_secondary_container = "#D0E6F2"; + std::string tertiary = "#C6C2EA"; + std::string on_tertiary = "#2F2D4D"; + std::string tertiary_container = "#454364"; + std::string on_tertiary_container = "#E3DFFF"; + std::string error = "#FFB4AB"; + std::string on_error = "#690005"; + std::string error_container = "#93000A"; + std::string on_error_container = "#FFDAD6"; + std::string background = "#0F1417"; + std::string on_background = "#DFE3E7"; + std::string surface = "#0F1417"; + std::string on_surface = "#DFE3E7"; + std::string surface_variant = "#40484C"; + std::string on_surface_variant = "#C0C8CD"; + std::string outline = "#8A9297"; + std::string outline_variant = "#40484C"; + std::string shadow = "#000000"; + std::string scrim = "#000000"; + std::string inverse_surface = "#DFE3E7"; + std::string inverse_on_surface = "#2C3134"; + std::string inverse_primary = "#126682"; + std::string primary_fixed = "#BEE9FF"; + std::string on_primary_fixed = "#001F2A"; + std::string primary_fixed_dim = "#8BD0F0"; + std::string on_primary_fixed_variant = "#004D64"; + std::string secondary_fixed = "#D0E6F2"; + std::string on_secondary_fixed = "#081E27"; + std::string secondary_fixed_dim = "#B4CAD6"; + std::string on_secondary_fixed_variant = "#354A54"; + std::string tertiary_fixed = "#E3DFFF"; + std::string on_tertiary_fixed = "#1A1836"; + std::string tertiary_fixed_dim = "#C6C2EA"; + std::string on_tertiary_fixed_variant = "#454364"; + std::string surface_dim = "#0F1417"; + std::string surface_bright = "#353A3D"; + std::string surface_container_lowest = "#0A0F11"; + std::string surface_container_low = "#171C1F"; + std::string surface_container = "#1B2023"; + std::string surface_container_high = "#262B2E"; + std::string surface_container_highest = "#303538"; + std::string disabled_elevated_button_bg = "#292D30"; + std::string success = "#8DF08B"; + std::string warning = "#EEF08B"; + std::string info = "#8BD0F0"; + std::string danger = "#F08B8B"; +}; + +inline MaterialColors default_colors; +} // namespace colors +} // namespace state_rviz_plugin +} // namespace autoware + +#endif // MATERIAL_COLORS_HPP_ diff --git a/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.hpp b/common/tier4_state_rviz_plugin/src/include/velocity_steering_factors_panel.hpp similarity index 100% rename from common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.hpp rename to common/tier4_state_rviz_plugin/src/include/velocity_steering_factors_panel.hpp diff --git a/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp b/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp index 6ea142ed66a1b..90ad18fe5af6c 100644 --- a/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp +++ b/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp @@ -14,7 +14,7 @@ // limitations under the License. // -#include "velocity_steering_factors_panel.hpp" +#include "include/velocity_steering_factors_panel.hpp" #include #include diff --git a/common/tier4_target_object_type_rviz_plugin/CMakeLists.txt b/common/tier4_target_object_type_rviz_plugin/CMakeLists.txt deleted file mode 100644 index ed458cf924e33..0000000000000 --- a/common/tier4_target_object_type_rviz_plugin/CMakeLists.txt +++ /dev/null @@ -1,25 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(tier4_target_object_type_rviz_plugin) - -find_package(autoware_cmake REQUIRED) -autoware_package() -find_package(OpenCV REQUIRED) -find_package(Qt5 REQUIRED Core Widgets) -set(QT_LIBRARIES Qt5::Widgets) -set(CMAKE_AUTOMOC ON) -set(CMAKE_INCLUDE_CURRENT_DIR ON) - -ament_auto_add_library(${PROJECT_NAME} SHARED - src/target_object_type_panel.hpp - src/target_object_type_panel.cpp -) -target_link_libraries(${PROJECT_NAME} - ${QT_LIBRARIES} - ${OpenCV_LIBRARIES} -) -pluginlib_export_plugin_description_file(rviz_common plugins/plugin_description.xml) - -ament_auto_package( - INSTALL_TO_SHARE - plugins -) diff --git a/common/tier4_target_object_type_rviz_plugin/README.md b/common/tier4_target_object_type_rviz_plugin/README.md deleted file mode 100644 index 1296bd3442ab3..0000000000000 --- a/common/tier4_target_object_type_rviz_plugin/README.md +++ /dev/null @@ -1,9 +0,0 @@ -# tier4_target_object_type_rviz_plugin - -This plugin allows you to check which types of the dynamic object is being used by each planner. - -![window](./image/window.png) - -## Limitations - -Currently, which parameters of which module to check are hardcoded. In the future, this will be parameterized using YAML. diff --git a/common/tier4_target_object_type_rviz_plugin/image/window.png b/common/tier4_target_object_type_rviz_plugin/image/window.png deleted file mode 100644 index 33aa9a1e5a26e..0000000000000 Binary files a/common/tier4_target_object_type_rviz_plugin/image/window.png and /dev/null differ diff --git a/common/tier4_target_object_type_rviz_plugin/package.xml b/common/tier4_target_object_type_rviz_plugin/package.xml deleted file mode 100644 index 04d2f28d9ba3e..0000000000000 --- a/common/tier4_target_object_type_rviz_plugin/package.xml +++ /dev/null @@ -1,28 +0,0 @@ - - - - tier4_target_object_type_rviz_plugin - 0.0.1 - The tier4_target_object_type_rviz_plugin package - Takamasa Horibe - Apache License 2.0 - - ament_cmake_auto - autoware_cmake - - cv_bridge - libqt5-core - libqt5-gui - libqt5-widgets - qtbase5-dev - rclcpp - rviz_common - rviz_rendering - ament_lint_auto - autoware_lint_common - - - ament_cmake - - - diff --git a/common/tier4_target_object_type_rviz_plugin/plugins/plugin_description.xml b/common/tier4_target_object_type_rviz_plugin/plugins/plugin_description.xml deleted file mode 100644 index eb3350e4333bd..0000000000000 --- a/common/tier4_target_object_type_rviz_plugin/plugins/plugin_description.xml +++ /dev/null @@ -1,9 +0,0 @@ - - - - TargetObjectTypePanel - - - diff --git a/common/tier4_target_object_type_rviz_plugin/src/target_object_type_panel.cpp b/common/tier4_target_object_type_rviz_plugin/src/target_object_type_panel.cpp deleted file mode 100644 index e014307942bab..0000000000000 --- a/common/tier4_target_object_type_rviz_plugin/src/target_object_type_panel.cpp +++ /dev/null @@ -1,316 +0,0 @@ -// Copyright 2023 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 "target_object_type_panel.hpp" - -#include -#include -#include -#include -#include - -TargetObjectTypePanel::TargetObjectTypePanel(QWidget * parent) : rviz_common::Panel(parent) -{ - node_ = std::make_shared("matrix_display_node"); - - setParameters(); - - matrix_widget_ = new QTableWidget(modules_.size(), targets_.size(), this); - for (size_t i = 0; i < modules_.size(); i++) { - matrix_widget_->setVerticalHeaderItem( - i, new QTableWidgetItem(QString::fromStdString(modules_[i]))); - } - for (size_t j = 0; j < targets_.size(); j++) { - matrix_widget_->setHorizontalHeaderItem( - j, new QTableWidgetItem(QString::fromStdString(targets_[j]))); - } - - updateMatrix(); - - reload_button_ = new QPushButton("Reload", this); - connect( - reload_button_, &QPushButton::clicked, this, &TargetObjectTypePanel::onReloadButtonClicked); - - QVBoxLayout * layout = new QVBoxLayout; - layout->addWidget(matrix_widget_); - layout->addWidget(reload_button_); - setLayout(layout); -} - -void TargetObjectTypePanel::onReloadButtonClicked() -{ - RCLCPP_INFO(node_->get_logger(), "Reload button clicked. Update parameter data."); - updateMatrix(); -} - -void TargetObjectTypePanel::setParameters() -{ - // Parameter will be investigated for these modules: - modules_ = { - "avoidance", - "avoidance_by_lane_change", - "dynamic_avoidance", - "lane_change", - "start_planner", - "goal_planner", - "crosswalk", - "surround_obstacle_checker", - "obstacle_cruise (inside)", - "obstacle_cruise (outside)", - "obstacle_stop", - "obstacle_slowdown"}; - - // Parameter will be investigated for targets in each module - targets_ = {"car", "truck", "bus", "trailer", "unknown", "bicycle", "motorcycle", "pedestrian"}; - - // TODO(Horibe): If the param naming strategy is aligned, this should be done automatically based - // on the modules_ and targets_. - - // default - ParamNameEnableObject default_param_name; - default_param_name.name.emplace("car", "car"); - default_param_name.name.emplace("truck", "truck"); - default_param_name.name.emplace("bus", "bus"); - default_param_name.name.emplace("trailer", "trailer"); - default_param_name.name.emplace("unknown", "unknown"); - default_param_name.name.emplace("bicycle", "bicycle"); - default_param_name.name.emplace("motorcycle", "motorcycle"); - default_param_name.name.emplace("pedestrian", "pedestrian"); - - // avoidance - { - const auto module = "avoidance"; - ParamNameEnableObject param_name; - param_name.node = - "/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner"; - param_name.ns = "avoidance.target_filtering.target_type"; - param_name.name = default_param_name.name; - param_names_.emplace(module, param_name); - } - - // avoidance_by_lane_change - { - const auto module = "avoidance_by_lane_change"; - ParamNameEnableObject param_name; - param_name.node = - "/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner"; - param_name.ns = "avoidance_by_lane_change.target_filtering.target_type"; - param_name.name = default_param_name.name; - param_names_.emplace(module, param_name); - } - - // lane_change - { - const auto module = "lane_change"; - ParamNameEnableObject param_name; - param_name.node = - "/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner"; - param_name.ns = "lane_change.target_object"; - param_name.name = default_param_name.name; - param_names_.emplace(module, param_name); - } - - // start_planner - { - const auto module = "start_planner"; - ParamNameEnableObject param_name; - param_name.node = - "/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner"; - param_name.ns = "start_planner.path_safety_check.target_filtering.object_types_to_check"; - param_name.name.emplace("car", "check_car"); - param_name.name.emplace("truck", "check_truck"); - param_name.name.emplace("bus", "check_bus"); - param_name.name.emplace("trailer", "check_trailer"); - param_name.name.emplace("unknown", "check_unknown"); - param_name.name.emplace("bicycle", "check_bicycle"); - param_name.name.emplace("motorcycle", "check_motorcycle"); - param_name.name.emplace("pedestrian", "check_pedestrian"); - param_names_.emplace(module, param_name); - } - - // goal_planner - { - const auto module = "goal_planner"; - ParamNameEnableObject param_name; - param_name.node = - "/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner"; - param_name.ns = "goal_planner.path_safety_check.target_filtering.object_types_to_check"; - param_name.name.emplace("car", "check_car"); - param_name.name.emplace("truck", "check_truck"); - param_name.name.emplace("bus", "check_bus"); - param_name.name.emplace("trailer", "check_trailer"); - param_name.name.emplace("unknown", "check_unknown"); - param_name.name.emplace("bicycle", "check_bicycle"); - param_name.name.emplace("motorcycle", "check_motorcycle"); - param_name.name.emplace("pedestrian", "check_pedestrian"); - param_names_.emplace(module, param_name); - } - - // dynamic_avoidance - { - const auto module = "dynamic_avoidance"; - ParamNameEnableObject param_name; - param_name.node = - "/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner"; - param_name.ns = "dynamic_avoidance.target_object"; - param_name.name = default_param_name.name; - param_names_.emplace(module, param_name); - } - - // crosswalk - { - const auto module = "crosswalk"; - ParamNameEnableObject param_name; - param_name.node = - "/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner"; - param_name.ns = "crosswalk.object_filtering.target_object"; - param_name.name = default_param_name.name; - param_names_.emplace(module, param_name); - } - - // obstacle cruise (inside) - { - const auto module = "obstacle_cruise (inside)"; - ParamNameEnableObject param_name; - param_name.node = - "/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner"; - param_name.ns = "common.cruise_obstacle_type.inside"; - param_name.name = default_param_name.name; - param_names_.emplace(module, param_name); - } - - // obstacle cruise (outside) - { - const auto module = "obstacle_cruise (outside)"; - ParamNameEnableObject param_name; - param_name.node = - "/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner"; - param_name.ns = "common.cruise_obstacle_type.outside"; - param_name.name = default_param_name.name; - param_names_.emplace(module, param_name); - } - - // surround_obstacle_check - { - const auto module = "surround_obstacle_checker"; - ParamNameEnableObject param_name; - param_name.node = - "/planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker"; - param_name.ns = ""; - param_name.name.emplace("car", "car.enable_check"); - param_name.name.emplace("truck", "truck.enable_check"); - param_name.name.emplace("bus", "bus.enable_check"); - param_name.name.emplace("trailer", "trailer.enable_check"); - param_name.name.emplace("unknown", "unknown.enable_check"); - param_name.name.emplace("bicycle", "bicycle.enable_check"); - param_name.name.emplace("motorcycle", "motorcycle.enable_check"); - param_name.name.emplace("pedestrian", "pedestrian.enable_check"); - param_names_.emplace(module, param_name); - } - - // obstacle stop - { - const auto module = "obstacle_stop"; - ParamNameEnableObject param_name; - param_name.node = - "/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner"; - param_name.ns = "common.stop_obstacle_type"; - param_name.name = default_param_name.name; - param_names_.emplace(module, param_name); - } - - // obstacle slowdown - { - const auto module = "obstacle_slowdown"; - ParamNameEnableObject param_name; - param_name.node = - "/planning/scenario_planning/lane_driving/motion_planning/obstacle_cruise_planner"; - param_name.ns = "common.slow_down_obstacle_type"; - param_name.name = default_param_name.name; - param_names_.emplace(module, param_name); - } -} - -void TargetObjectTypePanel::updateMatrix() -{ - // blue base - // const QColor color_in_use("#6eb6cc"); - // const QColor color_no_use("#1d3e48"); - // const QColor color_undefined("#9e9e9e"); - - // green base - const QColor color_in_use("#afff70"); - const QColor color_no_use("#44642b"); - const QColor color_undefined("#9e9e9e"); - - const auto set_undefined = [&](const auto i, const auto j) { - QTableWidgetItem * item = new QTableWidgetItem("N/A"); - item->setForeground(QBrush(Qt::black)); // set the text color to black - item->setBackground(color_undefined); - matrix_widget_->setItem(i, j, item); - }; - - for (size_t i = 0; i < modules_.size(); i++) { - const auto & module = modules_[i]; - - // Check if module exists in param_names_ - if (param_names_.find(module) == param_names_.end()) { - RCLCPP_WARN_STREAM(node_->get_logger(), module << " is not in the param names"); - continue; - } - - const auto & module_params = param_names_.at(module); - auto parameters_client = - std::make_shared(node_, module_params.node); - if (!parameters_client->wait_for_service(std::chrono::microseconds(500))) { - RCLCPP_WARN_STREAM( - node_->get_logger(), "Failed to find parameter service for node: " << module_params.node); - for (size_t j = 0; j < targets_.size(); j++) { - set_undefined(i, j); - } - continue; - } - - for (size_t j = 0; j < targets_.size(); j++) { - const auto & target = targets_[j]; - - // Check if target exists in module's name map - if (module_params.name.find(target) == module_params.name.end()) { - RCLCPP_WARN_STREAM( - node_->get_logger(), target << " parameter is not set in the " << module); - continue; - } - - std::string param_name = - (module_params.ns.empty() ? "" : module_params.ns + ".") + module_params.name.at(target); - auto parameter_result = parameters_client->get_parameters({param_name}); - - if (!parameter_result.empty()) { - bool value = parameter_result[0].as_bool(); - QTableWidgetItem * item = new QTableWidgetItem(value ? "O" : "X"); - item->setForeground(QBrush(value ? Qt::black : Qt::black)); // set the text color to black - item->setBackground(QBrush(value ? color_in_use : color_no_use)); - matrix_widget_->setItem(i, j, item); - } else { - RCLCPP_WARN_STREAM( - node_->get_logger(), - "Failed to get parameter " << module_params.node << " " << param_name); - - set_undefined(i, j); - } - } - } -} - -PLUGINLIB_EXPORT_CLASS(TargetObjectTypePanel, rviz_common::Panel) diff --git a/common/tier4_target_object_type_rviz_plugin/src/target_object_type_panel.hpp b/common/tier4_target_object_type_rviz_plugin/src/target_object_type_panel.hpp deleted file mode 100644 index 1f3934369bfba..0000000000000 --- a/common/tier4_target_object_type_rviz_plugin/src/target_object_type_panel.hpp +++ /dev/null @@ -1,60 +0,0 @@ -// Copyright 2023 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 TARGET_OBJECT_TYPE_PANEL_HPP_ -#define TARGET_OBJECT_TYPE_PANEL_HPP_ - -#include -#include -#include -#include -#include - -#include -#include -#include -#include - -class TargetObjectTypePanel : public rviz_common::Panel -{ - Q_OBJECT - -public: - explicit TargetObjectTypePanel(QWidget * parent = 0); - -protected: - QTableWidget * matrix_widget_; - std::shared_ptr node_; - std::vector modules_; - std::vector targets_; - - struct ParamNameEnableObject - { - std::string node; - std::string ns; - std::unordered_map name; - }; - std::unordered_map param_names_; - -private slots: - void onReloadButtonClicked(); - -private: - QPushButton * reload_button_; - - void updateMatrix(); - void setParameters(); -}; - -#endif // TARGET_OBJECT_TYPE_PANEL_HPP_ diff --git a/common/traffic_light_recognition_marker_publisher/Readme.md b/common/traffic_light_recognition_marker_publisher/Readme.md index 1cafc619ff6fb..6a51499c4e5da 100644 --- a/common/traffic_light_recognition_marker_publisher/Readme.md +++ b/common/traffic_light_recognition_marker_publisher/Readme.md @@ -1,4 +1,4 @@ -# path_distance_calculator +# Traffic Light Recognition Marker Publisher ## Purpose diff --git a/common/tvm_utility/example/yolo_v2_tiny/main.cpp b/common/tvm_utility/example/yolo_v2_tiny/main.cpp index 8a89436170894..8fd0cde3c306d 100644 --- a/common/tvm_utility/example/yolo_v2_tiny/main.cpp +++ b/common/tvm_utility/example/yolo_v2_tiny/main.cpp @@ -200,6 +200,8 @@ class PostProcessorYoloV2Tiny : public tvm_utility::pipeline::PostProcessor class_probabilities{}; float p_total = 0; diff --git a/control/autonomous_emergency_braking/README.md b/control/autonomous_emergency_braking/README.md index 28b7636ba82ac..23f4476d9659d 100644 --- a/control/autonomous_emergency_braking/README.md +++ b/control/autonomous_emergency_braking/README.md @@ -16,6 +16,24 @@ This module has following assumptions. ![aeb_range](./image/range.drawio.svg) +### IMU path generation: steering angle vs IMU's angular velocity + +Currently, the IMU-based path is generated using the angular velocity obtained by the IMU itself. It has been suggested that the steering angle could be used instead onf the angular velocity. + +The pros and cons of both approaches are: + +IMU angular velocity: + +- (+) Usually, it has high accuracy +- (-)Vehicle vibration might introduce noise. + +Steering angle: + +- (+) Not so noisy +- (-) May have a steering offset or a wrong gear ratio, and the steering angle of Autoware and the real steering may not be the same. + +For the moment, there are no plans to implement the steering angle on the path creation process of the AEB module. + ### Limitations - AEB might not be able to react with obstacles that are close to the ground. It depends on the performance of the pre-processing methods applied to the point cloud. @@ -86,20 +104,55 @@ where $v$ and $\omega$ are current longitudinal velocity and angular velocity re ### 3. Get target obstacles from the input point cloud -After generating the ego predicted path, we select target obstacles from the input point cloud. This obstacle filtering has two major steps, which are rough filtering and rigorous filtering. +After generating the ego predicted path, we select target obstacles from the input point cloud. This obstacle filtering has three major steps, which are rough filtering, noise filtering with clustering and rigorous filtering. #### Rough filtering -In rough filtering step, we select target obstacle with simple filter. Create a search area up to a certain distance (default 5[m]) away from the predicted path of the ego vehicle and ignore the point cloud (obstacles) that are not within it. The image of the rough filtering is illustrated below. +In rough filtering step, we select target obstacle with simple filter. Create a search area up to a certain distance (default is half of the ego vehicle width plus the `path_footprint_extra_margin` parameter) away from the predicted path of the ego vehicle and ignore the point cloud that are not within it. The image of the rough filtering is illustrated below. ![rough_filtering](./image/obstacle_filtering_1.drawio.svg) +#### Noise filtering with clustering and convex hulls + +To prevent the AEB from considering noisy points, euclidean clustering is performed on the filtered point cloud. The points in the point cloud that are not close enough to other points to form a cluster are discarded. The parameters `cluster_tolerance`, `minimum_cluster_size` and `maximum_cluster_size` can be used to tune the clustering and the size of objects to be ignored, for more information about the clustering method used by the AEB module, please check the official documentation on euclidean clustering of the PCL library: . + +Furthermore, a 2D convex hull is created around each detected cluster, the vertices of each hull represent the most extreme/outside points of the cluster. These vertices are then checked in the next step. + #### Rigorous filtering -After rough filtering, it performs a geometric collision check to determine whether the filtered obstacles actually have possibility to collide with the ego vehicle. In this check, the ego vehicle is represented as a rectangle, and the point cloud obstacles are represented as points. +After Noise filtering, it performs a geometric collision check to determine whether the filtered obstacles/hull vertices actually have possibility to collide with the ego vehicle. In this check, the ego vehicle is represented as a rectangle, and the point cloud obstacles are represented as points. Only the vertices with a possibility of collision are kept. ![rigorous_filtering](./image/obstacle_filtering_2.drawio.svg) +Finally, the vertex that is closest to the ego vehicle is chosen as the candidate for collision checking: Since rss distance is used to judge if a collision will happen or not, if the closest vertex to the ego is deemed to be safe, the rest of the vertices (and the points in the clusters) will also be safe. + +#### Obstacle velocity estimation + +Once the position of the closest obstacle/point is determined, the AEB modules uses the history of previously detected objects to estimate the closest object speed using the following equations: + +$$ +d_{t} = o_{time stamp} - prev_{time stamp} +$$ + +$$ +d_{pos} = norm(o_{pos} - prev_{pos}) +$$ + +$$ +v_{norm} = d_{pos} / d_{t} +$$ + +Where $o_{time stamp}$ and $prev_{time stamp}$ are the timestamps of the point clouds used to detect the current closest object and the closest object of the previous point cloud frame, and $o_{pos}$ and $prev_{pos}$ are the positions of those objects, respectively. + +Finally, the velocity vector is compared against the ego's predicted path to get the longitudinal velocity $v_{obj}$: + +$$ +v_{obj} = v_{norm} * Cos(yaw_{diff}) + v_{ego} +$$ + +where $yaw_{diff}$ is the difference in yaw between the ego path and the displacement vector $$v_{pos} = o_{pos} - prev_{pos} $$ and $v_{ego}$ is the ego's speed, which accounts for the movement of points caused by the ego moving and not the object. +All these equations are performed disregarding the z axis (in 2D). + ### 4. Collision check with target obstacles In the fourth step, it checks the collision with filtered obstacles using RSS distance. RSS is formulated as: diff --git a/control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml b/control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml index 82d5a4f12e002..68a42383feb1f 100644 --- a/control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml +++ b/control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml @@ -1,22 +1,38 @@ /**: ros__parameters: - publish_debug_pointcloud: false + # Ego path calculation use_predicted_trajectory: true - use_imu_path: true + use_imu_path: false + min_generated_path_length: 0.5 + imu_prediction_time_horizon: 1.5 + imu_prediction_time_interval: 0.1 + mpc_prediction_time_horizon: 1.5 + mpc_prediction_time_interval: 0.1 + + # Debug + publish_debug_pointcloud: false + + # Point cloud partitioning detection_range_min_height: 0.0 detection_range_max_height_margin: 0.0 voxel_grid_x: 0.05 voxel_grid_y: 0.05 voxel_grid_z: 100000.0 - min_generated_path_length: 0.5 + + # Point cloud cropping expand_width: 0.1 + path_footprint_extra_margin: 4.0 + + # Point cloud clustering + cluster_tolerance: 0.1 #[m] + minimum_cluster_size: 10 + maximum_cluster_size: 10000 + + # RSS distance collision check longitudinal_offset: 2.0 t_response: 1.0 a_ego_min: -3.0 a_obj_min: -1.0 - imu_prediction_time_horizon: 1.5 - imu_prediction_time_interval: 0.1 - mpc_prediction_time_horizon: 1.5 - mpc_prediction_time_interval: 0.1 - collision_keeping_sec: 0.0 + collision_keeping_sec: 2.0 + previous_obstacle_keep_time: 1.0 aeb_hz: 10.0 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 b8aad1c80dfea..27f04603d6a31 100644 --- a/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp +++ b/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp @@ -16,8 +16,11 @@ #define AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_ #include +#include #include #include +#include +#include #include #include @@ -39,12 +42,13 @@ #include #include +#include +#include #include -#include #include #include +#include #include - namespace autoware::motion::control::autonomous_emergency_braking { @@ -64,7 +68,6 @@ using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; using Path = std::vector; using Vector3 = geometry_msgs::msg::Vector3; - struct ObjectData { rclcpp::Time stamp; @@ -79,45 +82,171 @@ class CollisionDataKeeper public: explicit CollisionDataKeeper(rclcpp::Clock::SharedPtr clock) { clock_ = clock; } - void setTimeout(const double timeout_sec) { timeout_sec_ = timeout_sec; } + void setTimeout(const double collision_keep_time, const double previous_obstacle_keep_time) + { + collision_keep_time_ = collision_keep_time; + previous_obstacle_keep_time_ = previous_obstacle_keep_time; + } + + std::pair getTimeout() + { + return {collision_keep_time_, previous_obstacle_keep_time_}; + } - bool checkExpired() + bool checkObjectDataExpired(std::optional & data, const double timeout) { - if (data_ && (clock_->now() - data_->stamp).seconds() > timeout_sec_) { - data_.reset(); + if (!data.has_value()) return true; + const auto now = clock_->now(); + const auto & prev_obj = data.value(); + const auto & data_time_stamp = prev_obj.stamp; + if ((now - data_time_stamp).nanoseconds() * 1e-9 > timeout) { + data = std::nullopt; + return true; } - return (data_ == nullptr); + return false; + } + + bool checkCollisionExpired() + { + return this->checkObjectDataExpired(closest_object_, collision_keep_time_); + } + + bool checkPreviousObjectDataExpired() + { + return this->checkObjectDataExpired(prev_closest_object_, previous_obstacle_keep_time_); + } + + ObjectData get() const + { + return (closest_object_.has_value()) ? closest_object_.value() : ObjectData(); + } + + ObjectData getPreviousObjectData() const + { + return (prev_closest_object_.has_value()) ? prev_closest_object_.value() : ObjectData(); + } + + void setCollisionData(const ObjectData & data) + { + closest_object_ = std::make_optional(data); + } + + void setPreviousObjectData(const ObjectData & data) + { + prev_closest_object_ = std::make_optional(data); } - void update(const ObjectData & data) { data_.reset(new ObjectData(data)); } + void resetVelocityHistory() { obstacle_velocity_history_.clear(); } - ObjectData get() + void updateVelocityHistory( + const double current_object_velocity, const rclcpp::Time & current_object_velocity_time_stamp) { - if (data_) { - return *data_; - } else { - return ObjectData(); + // remove old msg from deque + const auto now = clock_->now(); + 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)); + } + + std::optional getMedianObstacleVelocity() const + { + if (obstacle_velocity_history_.empty()) return std::nullopt; + std::vector raw_velocities; + for (const auto & vel_time_pair : obstacle_velocity_history_) { + raw_velocities.emplace_back(vel_time_pair.first); + } + + const size_t med1 = (raw_velocities.size() % 2 == 0) ? (raw_velocities.size()) / 2 - 1 + : (raw_velocities.size()) / 2.0; + const size_t med2 = (raw_velocities.size()) / 2.0; + std::nth_element(raw_velocities.begin(), raw_velocities.begin() + med1, raw_velocities.end()); + const double vel1 = raw_velocities.at(med1); + std::nth_element(raw_velocities.begin(), raw_velocities.begin() + med2, raw_velocities.end()); + const double vel2 = raw_velocities.at(med2); + return (vel1 + vel2) / 2.0; + } + + std::optional calcObjectSpeedFromHistory( + const ObjectData & closest_object, const Path & path, const double current_ego_speed) + { + if (this->checkPreviousObjectDataExpired()) { + this->setPreviousObjectData(closest_object); + this->resetVelocityHistory(); + return std::nullopt; + } + + const auto estimated_velocity_opt = std::invoke([&]() -> std::optional { + const auto & prev_object = this->getPreviousObjectData(); + const double p_dt = + (closest_object.stamp.nanoseconds() - prev_object.stamp.nanoseconds()) * 1e-9; + if (p_dt < std::numeric_limits::epsilon()) return std::nullopt; + const auto & nearest_collision_point = closest_object.position; + const auto & prev_collision_point = prev_object.position; + + const double p_dx = nearest_collision_point.x - prev_collision_point.x; + const double p_dy = nearest_collision_point.y - prev_collision_point.y; + const double p_dist = std::hypot(p_dx, p_dy); + const double p_yaw = std::atan2(p_dy, p_dx); + const double p_vel = p_dist / p_dt; + + const auto nearest_idx = motion_utils::findNearestIndex(path, nearest_collision_point); + const auto & nearest_path_pose = path.at(nearest_idx); + const auto & traj_yaw = tf2::getYaw(nearest_path_pose.orientation); + const auto estimated_velocity = p_vel * std::cos(p_yaw - traj_yaw) + current_ego_speed; + + // Current RSS distance calculation does not account for negative velocities + return (estimated_velocity > 0.0) ? estimated_velocity : 0.0; + }); + + if (!estimated_velocity_opt.has_value()) { + return std::nullopt; } + + const auto & estimated_velocity = estimated_velocity_opt.value(); + this->setPreviousObjectData(closest_object); + this->updateVelocityHistory(estimated_velocity, closest_object.stamp); + return this->getMedianObstacleVelocity(); } private: - std::unique_ptr data_; - double timeout_sec_{0.0}; + std::optional prev_closest_object_{std::nullopt}; + std::optional closest_object_{std::nullopt}; + double collision_keep_time_{0.0}; + double previous_obstacle_keep_time_{0.0}; + + std::deque> obstacle_velocity_history_; rclcpp::Clock::SharedPtr clock_; }; +static rclcpp::SensorDataQoS SingleDepthSensorQoS() +{ + rclcpp::SensorDataQoS qos; + qos.get_rmw_qos_profile().depth = 1; + return qos; +} + class AEB : public rclcpp::Node { public: explicit AEB(const rclcpp::NodeOptions & node_options); // subscriber - rclcpp::Subscription::SharedPtr sub_point_cloud_; - rclcpp::Subscription::SharedPtr sub_velocity_; - rclcpp::Subscription::SharedPtr sub_imu_; - rclcpp::Subscription::SharedPtr sub_predicted_traj_; - rclcpp::Subscription::SharedPtr sub_autoware_state_; - + tier4_autoware_utils::InterProcessPollingSubscriber sub_point_cloud_{ + this, "~/input/pointcloud", SingleDepthSensorQoS()}; + tier4_autoware_utils::InterProcessPollingSubscriber sub_velocity_{ + this, "~/input/velocity"}; + tier4_autoware_utils::InterProcessPollingSubscriber sub_imu_{this, "~/input/imu"}; + tier4_autoware_utils::InterProcessPollingSubscriber sub_predicted_traj_{ + this, "~/input/predicted_trajectory"}; + tier4_autoware_utils::InterProcessPollingSubscriber sub_autoware_state_{ + this, "/autoware/state"}; // publisher rclcpp::Publisher::SharedPtr pub_obstacle_pointcloud_; rclcpp::Publisher::SharedPtr debug_ego_path_publisher_; // debug @@ -127,35 +256,46 @@ class AEB : public rclcpp::Node // callback void onPointCloud(const PointCloud2::ConstSharedPtr input_msg); - void onVelocity(const VelocityReport::ConstSharedPtr input_msg); void onImu(const Imu::ConstSharedPtr input_msg); 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(); + bool fetchLatestData(); // main function void onCheckCollision(DiagnosticStatusWrapper & stat); bool checkCollision(MarkerArray & debug_markers); - bool hasCollision( - const double current_v, const Path & ego_path, const std::vector & objects); + bool hasCollision(const double current_v, const ObjectData & closest_object); + + Path generateEgoPath(const double curr_v, const double curr_w); + std::optional generateEgoPath(const Trajectory & predicted_traj); + std::vector generatePathFootprint(const Path & path, const double extra_width_margin); + + void createObjectDataUsingPointCloudClusters( + const Path & ego_path, const std::vector & ego_polys, const rclcpp::Time & stamp, + std::vector & objects, + const pcl::PointCloud::Ptr obstacle_points_ptr); + + void cropPointCloudWithEgoFootprintPath( + const std::vector & ego_polys, pcl::PointCloud::Ptr filtered_objects); - Path generateEgoPath(const double curr_v, const double curr_w, std::vector & polygons); - std::optional generateEgoPath( - const Trajectory & predicted_traj, std::vector & polygons); - void createObjectData( + void createObjectDataUsingPointCloudClusters( const Path & ego_path, const std::vector & ego_polys, const rclcpp::Time & stamp, std::vector & objects); + void cropPointCloudWithEgoFootprintPath(const std::vector & ego_polys); void addMarker( const rclcpp::Time & current_time, const Path & path, const std::vector & polygons, - const std::vector & objects, const double color_r, const double color_g, - const double color_b, const double color_a, const std::string & ns, - MarkerArray & debug_markers); + const std::vector & objects, const std::optional & closest_object, + const double color_r, const double color_g, const double color_b, const double color_a, + const std::string & ns, MarkerArray & debug_markers); void addCollisionMarker(const ObjectData & data, MarkerArray & debug_markers); + std::optional calcObjectSpeedFromHistory( + const ObjectData & closest_object, const Path & path, const double current_ego_speed); + PointCloud2::SharedPtr obstacle_ros_pointcloud_ptr_{nullptr}; VelocityReport::ConstSharedPtr current_velocity_ptr_{nullptr}; Vector3::SharedPtr angular_velocity_ptr_{nullptr}; @@ -175,6 +315,7 @@ class AEB : public rclcpp::Node bool publish_debug_pointcloud_; bool use_predicted_trajectory_; bool use_imu_path_; + double path_footprint_extra_margin_; double detection_range_min_height_; double detection_range_max_height_margin_; double voxel_grid_x_; @@ -186,11 +327,16 @@ class AEB : public rclcpp::Node double t_response_; double a_ego_min_; double a_obj_min_; + double cluster_tolerance_; + int minimum_cluster_size_; + int maximum_cluster_size_; double imu_prediction_time_horizon_; double imu_prediction_time_interval_; 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/package.xml b/control/autonomous_emergency_braking/package.xml index 1ac255c21921b..68c070a86dd97 100644 --- a/control/autonomous_emergency_braking/package.xml +++ b/control/autonomous_emergency_braking/package.xml @@ -7,6 +7,7 @@ Takamasa Horibe Tomoya Kimura Mamoru Sobue + Daniel Sanchez Apache License 2.0 diff --git a/control/autonomous_emergency_braking/src/node.cpp b/control/autonomous_emergency_braking/src/node.cpp index 8c830812078b6..71eb92a4e95fb 100644 --- a/control/autonomous_emergency_braking/src/node.cpp +++ b/control/autonomous_emergency_braking/src/node.cpp @@ -14,17 +14,27 @@ #include "autonomous_emergency_braking/node.hpp" -#include +#include +#include #include #include #include +#include +#include +#include #include +#include +#include +#include #include #include +#include +#include +#include +#include #include - #ifdef ROS_DISTRO_GALACTIC #include #include @@ -34,8 +44,6 @@ #include #endif -#include -#include namespace autoware::motion::control::autonomous_emergency_braking { using diagnostic_msgs::msg::DiagnosticStatus; @@ -97,38 +105,22 @@ AEB::AEB(const rclcpp::NodeOptions & node_options) vehicle_info_(vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo()), collision_data_keeper_(this->get_clock()) { - // Subscribers - sub_point_cloud_ = this->create_subscription( - "~/input/pointcloud", rclcpp::SensorDataQoS(), - std::bind(&AEB::onPointCloud, this, std::placeholders::_1)); - - sub_velocity_ = this->create_subscription( - "~/input/velocity", rclcpp::QoS{1}, std::bind(&AEB::onVelocity, this, std::placeholders::_1)); - - sub_imu_ = this->create_subscription( - "~/input/imu", rclcpp::QoS{1}, std::bind(&AEB::onImu, this, std::placeholders::_1)); - - sub_predicted_traj_ = this->create_subscription( - "~/input/predicted_trajectory", rclcpp::QoS{1}, - std::bind(&AEB::onPredictedTrajectory, this, std::placeholders::_1)); - - sub_autoware_state_ = this->create_subscription( - "/autoware/state", rclcpp::QoS{1}, - std::bind(&AEB::onAutowareState, this, std::placeholders::_1)); - // Publisher - pub_obstacle_pointcloud_ = - this->create_publisher("~/debug/obstacle_pointcloud", 1); - debug_ego_path_publisher_ = this->create_publisher("~/debug/markers", 1); - + { + pub_obstacle_pointcloud_ = + this->create_publisher("~/debug/obstacle_pointcloud", 1); + debug_ego_path_publisher_ = this->create_publisher("~/debug/markers", 1); + } // Diagnostics - updater_.setHardwareID("autonomous_emergency_braking"); - updater_.add("aeb_emergency_stop", this, &AEB::onCheckCollision); - + { + updater_.setHardwareID("autonomous_emergency_braking"); + updater_.add("aeb_emergency_stop", this, &AEB::onCheckCollision); + } // parameter publish_debug_pointcloud_ = declare_parameter("publish_debug_pointcloud"); use_predicted_trajectory_ = declare_parameter("use_predicted_trajectory"); use_imu_path_ = declare_parameter("use_imu_path"); + path_footprint_extra_margin_ = declare_parameter("path_footprint_extra_margin"); detection_range_min_height_ = declare_parameter("detection_range_min_height"); detection_range_max_height_margin_ = declare_parameter("detection_range_max_height_margin"); @@ -141,28 +133,79 @@ AEB::AEB(const rclcpp::NodeOptions & node_options) t_response_ = declare_parameter("t_response"); a_ego_min_ = declare_parameter("a_ego_min"); a_obj_min_ = declare_parameter("a_obj_min"); + + cluster_tolerance_ = declare_parameter("cluster_tolerance"); + minimum_cluster_size_ = declare_parameter("minimum_cluster_size"); + maximum_cluster_size_ = declare_parameter("maximum_cluster_size"); + imu_prediction_time_horizon_ = declare_parameter("imu_prediction_time_horizon"); imu_prediction_time_interval_ = declare_parameter("imu_prediction_time_interval"); mpc_prediction_time_horizon_ = declare_parameter("mpc_prediction_time_horizon"); mpc_prediction_time_interval_ = declare_parameter("mpc_prediction_time_interval"); - const auto collision_keeping_sec = declare_parameter("collision_keeping_sec"); - collision_data_keeper_.setTimeout(collision_keeping_sec); + { // Object history data keeper setup + const auto previous_obstacle_keep_time = + declare_parameter("previous_obstacle_keep_time"); + const auto collision_keeping_sec = declare_parameter("collision_keeping_sec"); + 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, get_clock(), period_ns, std::bind(&AEB::onTimer, this)); + timer_ = rclcpp::create_timer(this, this->get_clock(), period_ns, std::bind(&AEB::onTimer, this)); } -void AEB::onTimer() +rcl_interfaces::msg::SetParametersResult AEB::onParameter( + const std::vector & parameters) { - updater_.force_update(); + 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::onVelocity(const VelocityReport::ConstSharedPtr input_msg) +void AEB::onTimer() { - current_velocity_ptr_ = input_msg; + updater_.force_update(); } void AEB::onImu(const Imu::ConstSharedPtr input_msg) @@ -184,17 +227,6 @@ void AEB::onImu(const Imu::ConstSharedPtr input_msg) tf2::doTransform(input_msg->angular_velocity, *angular_velocity_ptr_, transform_stamped); } -void AEB::onPredictedTrajectory( - const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr input_msg) -{ - predicted_traj_ptr_ = input_msg; -} - -void AEB::onAutowareState(const AutowareState::ConstSharedPtr input_msg) -{ - autoware_state_ = input_msg; -} - void AEB::onPointCloud(const PointCloud2::ConstSharedPtr input_msg) { PointCloud::Ptr pointcloud_ptr(new PointCloud); @@ -242,36 +274,50 @@ void AEB::onPointCloud(const PointCloud2::ConstSharedPtr input_msg) filter.filter(*no_height_filtered_pointcloud_ptr); obstacle_ros_pointcloud_ptr_ = std::make_shared(); + pcl::toROSMsg(*no_height_filtered_pointcloud_ptr, *obstacle_ros_pointcloud_ptr_); obstacle_ros_pointcloud_ptr_->header = input_msg->header; - if (publish_debug_pointcloud_) { - pub_obstacle_pointcloud_->publish(*obstacle_ros_pointcloud_ptr_); - } } -bool AEB::isDataReady() +bool AEB::fetchLatestData() { const auto missing = [this](const auto & name) { RCLCPP_INFO_SKIPFIRST_THROTTLE(get_logger(), *get_clock(), 5000, "[AEB] waiting for %s", name); return false; }; + current_velocity_ptr_ = sub_velocity_.takeData(); if (!current_velocity_ptr_) { return missing("ego velocity"); } + const auto pointcloud_ptr = sub_point_cloud_.takeData(); + if (!pointcloud_ptr) { + return missing("object pointcloud message"); + } + onPointCloud(pointcloud_ptr); if (!obstacle_ros_pointcloud_ptr_) { return missing("object pointcloud"); } + const auto imu_ptr = sub_imu_.takeData(); + if (use_imu_path_) { + if (!imu_ptr) { + return missing("imu message"); + } + // imu_ptr is valid + onImu(imu_ptr); + } if (use_imu_path_ && !angular_velocity_ptr_) { return missing("imu"); } + predicted_traj_ptr_ = sub_predicted_traj_.takeData(); if (use_predicted_trajectory_ && !predicted_traj_ptr_) { return missing("control predicted trajectory"); } + autoware_state_ = sub_autoware_state_.takeData(); if (!autoware_state_) { return missing("autoware_state"); } @@ -284,13 +330,14 @@ void AEB::onCheckCollision(DiagnosticStatusWrapper & stat) MarkerArray debug_markers; checkCollision(debug_markers); - if (!collision_data_keeper_.checkExpired()) { + if (!collision_data_keeper_.checkCollisionExpired()) { const std::string error_msg = "[AEB]: Emergency Brake"; const auto diag_level = DiagnosticStatus::ERROR; stat.summary(diag_level, error_msg); const auto & data = collision_data_keeper_.get(); stat.addf("RSS", "%.2f", data.rss); stat.addf("Distance", "%.2f", data.distance_to_object); + stat.addf("Object Speed", "%.2f", data.velocity); addCollisionMarker(data, debug_markers); } else { const std::string error_msg = "[AEB]: No Collision"; @@ -304,8 +351,10 @@ void AEB::onCheckCollision(DiagnosticStatusWrapper & stat) bool AEB::checkCollision(MarkerArray & debug_markers) { + using colorTuple = std::tuple; + // step1. check data - if (!isDataReady()) { + if (!fetchLatestData()) { return false; } @@ -320,86 +369,114 @@ bool AEB::checkCollision(MarkerArray & debug_markers) return false; } - // step3. create ego path based on sensor data - bool has_collision_ego = false; - if (use_imu_path_) { - std::vector ego_polys; - const double current_w = angular_velocity_ptr_->z; - constexpr double color_r = 0.0 / 256.0; - constexpr double color_g = 148.0 / 256.0; - constexpr double color_b = 205.0 / 256.0; - constexpr double color_a = 0.999; - const auto current_time = get_clock()->now(); - const auto ego_path = generateEgoPath(current_v, current_w, ego_polys); - std::vector objects; - createObjectData(ego_path, ego_polys, current_time, objects); - has_collision_ego = hasCollision(current_v, ego_path, objects); - - std::string ns = "ego"; - addMarker( - current_time, ego_path, ego_polys, objects, color_r, color_g, color_b, color_a, ns, - debug_markers); - } - - // step4. transform predicted trajectory from control module - bool has_collision_predicted = false; - if (use_predicted_trajectory_) { - std::vector predicted_polys; - const auto predicted_traj_ptr = predicted_traj_ptr_; - constexpr double color_r = 0.0; - constexpr double color_g = 100.0 / 256.0; - constexpr double color_b = 0.0; - constexpr double color_a = 0.999; - const auto current_time = predicted_traj_ptr->header.stamp; - const auto predicted_path_opt = generateEgoPath(*predicted_traj_ptr, predicted_polys); - if (predicted_path_opt) { - const auto & predicted_path = predicted_path_opt.value(); - std::vector objects; - createObjectData(predicted_path, predicted_polys, current_time, objects); - has_collision_predicted = hasCollision(current_v, predicted_path, objects); - - std::string ns = "predicted"; + auto check_collision = [&]( + const auto & path, const colorTuple & debug_colors, + const std::string & debug_ns, + pcl::PointCloud::Ptr filtered_objects) { + // Crop out Pointcloud using an extra wide ego path + const auto expanded_ego_polys = + generatePathFootprint(path, expand_width_ + path_footprint_extra_margin_); + cropPointCloudWithEgoFootprintPath(expanded_ego_polys, filtered_objects); + + // Check which points of the cropped point cloud are on the ego path, and get the closest one + std::vector objects_from_point_clusters; + const auto ego_polys = generatePathFootprint(path, expand_width_); + const auto current_time = obstacle_ros_pointcloud_ptr_->header.stamp; + createObjectDataUsingPointCloudClusters( + path, ego_polys, current_time, objects_from_point_clusters, filtered_objects); + + // Get only the closest object and calculate its speed + const auto closest_object_point = std::invoke([&]() -> std::optional { + const auto closest_object_point_itr = std::min_element( + objects_from_point_clusters.begin(), objects_from_point_clusters.end(), + [](const auto & o1, const auto & o2) { + return o1.distance_to_object < o2.distance_to_object; + }); + + if (closest_object_point_itr == objects_from_point_clusters.end()) { + return std::nullopt; + } + const auto closest_object_speed = collision_data_keeper_.calcObjectSpeedFromHistory( + *closest_object_point_itr, path, current_v); + if (!closest_object_speed.has_value()) { + return std::nullopt; + } + closest_object_point_itr->velocity = closest_object_speed.value(); + return std::make_optional(*closest_object_point_itr); + }); + + // Add debug markers + { + const auto [color_r, color_g, color_b, color_a] = debug_colors; addMarker( - current_time, predicted_path, predicted_polys, objects, color_r, color_g, color_b, color_a, - ns, debug_markers); + this->get_clock()->now(), path, ego_polys, objects_from_point_clusters, + closest_object_point, color_r, color_g, color_b, color_a, debug_ns, debug_markers); } - } + // check collision using rss distance + return (closest_object_point.has_value()) + ? hasCollision(current_v, closest_object_point.value()) + : false; + }; - return has_collision_ego || has_collision_predicted; + // step3. make function to check collision with ego path created with sensor data + const auto has_collision_ego = [&](pcl::PointCloud::Ptr filtered_objects) -> bool { + if (!use_imu_path_) return false; + const double current_w = angular_velocity_ptr_->z; + constexpr colorTuple debug_color = {0.0 / 256.0, 148.0 / 256.0, 205.0 / 256.0, 0.999}; + const std::string ns = "ego"; + const auto ego_path = generateEgoPath(current_v, current_w); + + return check_collision(ego_path, debug_color, ns, filtered_objects); + }; + + // step4. make function to check collision with predicted trajectory from control module + const auto has_collision_predicted = + [&](pcl::PointCloud::Ptr filtered_objects) -> bool { + if (!use_predicted_trajectory_ || !predicted_traj_ptr_) return false; + const auto predicted_traj_ptr = predicted_traj_ptr_; + const auto predicted_path_opt = generateEgoPath(*predicted_traj_ptr); + + if (!predicted_path_opt) return false; + constexpr colorTuple debug_color = {0.0 / 256.0, 100.0 / 256.0, 0.0 / 256.0, 0.999}; + const std::string ns = "predicted"; + const auto & predicted_path = predicted_path_opt.value(); + + return check_collision(predicted_path, debug_color, ns, filtered_objects); + }; + + // Data of filtered point cloud + pcl::PointCloud::Ptr filtered_objects(new PointCloud); + // evaluate if there is a collision for both paths + const bool has_collision = + has_collision_ego(filtered_objects) || has_collision_predicted(filtered_objects); + + // Debug print + if (!filtered_objects->empty() && publish_debug_pointcloud_) { + const auto filtered_objects_ros_pointcloud_ptr_ = std::make_shared(); + pcl::toROSMsg(*filtered_objects, *filtered_objects_ros_pointcloud_ptr_); + pub_obstacle_pointcloud_->publish(*filtered_objects_ros_pointcloud_ptr_); + } + return has_collision; } -bool AEB::hasCollision( - const double current_v, const Path & ego_path, const std::vector & objects) +bool AEB::hasCollision(const double current_v, const ObjectData & closest_object) { - // calculate RSS - const auto current_p = tier4_autoware_utils::createPoint( - ego_path[0].position.x, ego_path[0].position.y, ego_path[0].position.z); + const double & obj_v = closest_object.velocity; const double & t = t_response_; - for (const auto & obj : objects) { - const double & obj_v = obj.velocity; - const double rss_dist = current_v * t + (current_v * current_v) / (2 * std::fabs(a_ego_min_)) - - obj_v * obj_v / (2 * std::fabs(a_obj_min_)) + longitudinal_offset_; - - // check the object is front the ego or not - if ((obj.position.x - ego_path[0].position.x) > 0) { - const double dist_ego_to_object = - motion_utils::calcSignedArcLength(ego_path, current_p, obj.position) - - vehicle_info_.max_longitudinal_offset_m; - if (dist_ego_to_object < rss_dist) { - // collision happens - ObjectData collision_data = obj; - collision_data.rss = rss_dist; - collision_data.distance_to_object = dist_ego_to_object; - collision_data_keeper_.update(collision_data); - return true; - } - } + const double rss_dist = current_v * t + (current_v * current_v) / (2 * std::fabs(a_ego_min_)) - + obj_v * obj_v / (2 * std::fabs(a_obj_min_)) + longitudinal_offset_; + if (closest_object.distance_to_object < rss_dist) { + // collision happens + ObjectData collision_data = closest_object; + collision_data.rss = rss_dist; + collision_data.distance_to_object = closest_object.distance_to_object; + collision_data_keeper_.setCollisionData(collision_data); + return true; } return false; } -Path AEB::generateEgoPath( - const double curr_v, const double curr_w, std::vector & polygons) +Path AEB::generateEgoPath(const double curr_v, const double curr_w) { Path path; double curr_x = 0.0; @@ -444,17 +521,10 @@ Path AEB::generateEgoPath( } path.push_back(current_pose); } - - // generate ego polygons - polygons.resize(path.size() - 1); - for (size_t i = 0; i < path.size() - 1; ++i) { - polygons.at(i) = createPolygon(path.at(i), path.at(i + 1), vehicle_info_, expand_width_); - } return path; } -std::optional AEB::generateEgoPath( - const Trajectory & predicted_traj, std::vector & polygons) +std::optional AEB::generateEgoPath(const Trajectory & predicted_traj) { if (predicted_traj.points.empty()) { return std::nullopt; @@ -482,35 +552,82 @@ std::optional AEB::generateEgoPath( break; } } - // create polygon - polygons.resize(path.size()); + return path; +} + +std::vector AEB::generatePathFootprint( + const Path & path, const double extra_width_margin) +{ + std::vector polygons; for (size_t i = 0; i < path.size() - 1; ++i) { - polygons.at(i) = createPolygon(path.at(i), path.at(i + 1), vehicle_info_, expand_width_); + polygons.push_back( + createPolygon(path.at(i), path.at(i + 1), vehicle_info_, extra_width_margin)); } - return path; + return polygons; } -void AEB::createObjectData( - const Path & ego_path, const std::vector & ego_polys, - const rclcpp::Time & stamp, std::vector & objects) +void AEB::createObjectDataUsingPointCloudClusters( + const Path & ego_path, const std::vector & ego_polys, const rclcpp::Time & stamp, + std::vector & objects, const pcl::PointCloud::Ptr obstacle_points_ptr) { // check if the predicted path has valid number of points - if (ego_path.size() < 2 || ego_polys.empty()) { + if (ego_path.size() < 2 || ego_polys.empty() || obstacle_points_ptr->empty()) { return; } - PointCloud::Ptr obstacle_points_ptr(new PointCloud); - pcl::fromROSMsg(*obstacle_ros_pointcloud_ptr_, *obstacle_points_ptr); - for (const auto & point : obstacle_points_ptr->points) { + // eliminate noisy points by only considering points belonging to clusters of at least a certain + // size + const std::vector cluster_indices = std::invoke([&]() { + std::vector cluster_idx; + pcl::search::KdTree::Ptr tree(new pcl::search::KdTree); + tree->setInputCloud(obstacle_points_ptr); + pcl::EuclideanClusterExtraction ec; + ec.setClusterTolerance(cluster_tolerance_); + ec.setMinClusterSize(minimum_cluster_size_); + ec.setMaxClusterSize(maximum_cluster_size_); + ec.setSearchMethod(tree); + ec.setInputCloud(obstacle_points_ptr); + ec.extract(cluster_idx); + return cluster_idx; + }); + + PointCloud::Ptr points_belonging_to_cluster_hulls(new PointCloud); + for (const auto & indices : cluster_indices) { + PointCloud::Ptr cluster(new PointCloud); + for (const auto & index : indices.indices) { + cluster->push_back((*obstacle_points_ptr)[index]); + } + // Make a 2d convex hull for the objects + pcl::ConvexHull hull; + hull.setDimension(2); + hull.setInputCloud(cluster); + std::vector polygons; + PointCloud::Ptr surface_hull(new pcl::PointCloud); + hull.reconstruct(*surface_hull, polygons); + for (const auto & p : *surface_hull) { + points_belonging_to_cluster_hulls->push_back(p); + } + } + + // select points inside the ego footprint path + const auto current_p = tier4_autoware_utils::createPoint( + ego_path[0].position.x, ego_path[0].position.y, ego_path[0].position.z); + + for (const auto & p : *points_belonging_to_cluster_hulls) { + const auto obj_position = tier4_autoware_utils::createPoint(p.x, p.y, p.z); + const double dist_ego_to_object = + motion_utils::calcSignedArcLength(ego_path, current_p, obj_position) - + vehicle_info_.max_longitudinal_offset_m; + // objects behind ego are ignored + if (dist_ego_to_object < 0.0) continue; + ObjectData obj; obj.stamp = stamp; - obj.position = tier4_autoware_utils::createPoint(point.x, point.y, point.z); + obj.position = obj_position; obj.velocity = 0.0; - const Point2d obj_point(point.x, point.y); - const double lat_dist = motion_utils::calcLateralOffset(ego_path, obj.position); - if (lat_dist > 5.0) { - continue; - } + obj.distance_to_object = dist_ego_to_object; + + const Point2d obj_point(p.x, p.y); for (const auto & ego_poly : ego_polys) { if (bg::within(obj_point, ego_poly)) { objects.push_back(obj); @@ -520,10 +637,41 @@ void AEB::createObjectData( } } +void AEB::cropPointCloudWithEgoFootprintPath( + const std::vector & ego_polys, pcl::PointCloud::Ptr filtered_objects) +{ + PointCloud::Ptr full_points_ptr(new PointCloud); + pcl::fromROSMsg(*obstacle_ros_pointcloud_ptr_, *full_points_ptr); + // Create a Point cloud with the points of the ego footprint + PointCloud::Ptr path_polygon_points(new PointCloud); + std::for_each(ego_polys.begin(), ego_polys.end(), [&](const auto & poly) { + std::for_each(poly.outer().begin(), poly.outer().end(), [&](const auto & p) { + pcl::PointXYZ point(p.x(), p.y(), 0.0); + path_polygon_points->push_back(point); + }); + }); + // Make a surface hull with the ego footprint to filter out points + pcl::ConvexHull hull; + hull.setDimension(2); + hull.setInputCloud(path_polygon_points); + std::vector polygons; + pcl::PointCloud::Ptr surface_hull(new pcl::PointCloud); + hull.reconstruct(*surface_hull, polygons); + // Filter out points outside of the path's convex hull + pcl::CropHull path_polygon_hull_filter; + path_polygon_hull_filter.setDim(2); + path_polygon_hull_filter.setInputCloud(full_points_ptr); + path_polygon_hull_filter.setHullIndices(polygons); + path_polygon_hull_filter.setHullCloud(surface_hull); + path_polygon_hull_filter.filter(*filtered_objects); + filtered_objects->header.stamp = full_points_ptr->header.stamp; +} + void AEB::addMarker( const rclcpp::Time & current_time, const Path & path, const std::vector & polygons, - const std::vector & objects, const double color_r, const double color_g, - const double color_b, const double color_a, const std::string & ns, MarkerArray & debug_markers) + const std::vector & objects, const std::optional & closest_object, + const double color_r, const double color_g, const double color_b, const double color_a, + const std::string & ns, MarkerArray & debug_markers) { auto path_marker = tier4_autoware_utils::createDefaultMarker( "base_link", current_time, ns + "_path", 0L, Marker::LINE_STRIP, @@ -553,12 +701,29 @@ void AEB::addMarker( auto object_data_marker = tier4_autoware_utils::createDefaultMarker( "base_link", current_time, ns + "_objects", 0, Marker::SPHERE_LIST, - tier4_autoware_utils::createMarkerScale(0.05, 0.05, 0.05), + tier4_autoware_utils::createMarkerScale(0.5, 0.5, 0.5), tier4_autoware_utils::createMarkerColor(color_r, color_g, color_b, color_a)); for (const auto & e : objects) { object_data_marker.points.push_back(e.position); } debug_markers.markers.push_back(object_data_marker); + + // Visualize planner type text + if (closest_object.has_value()) { + const auto & obj = closest_object.value(); + const auto color = tier4_autoware_utils::createMarkerColor(0.95, 0.95, 0.95, 0.999); + auto closest_object_velocity_marker_array = tier4_autoware_utils::createDefaultMarker( + "base_link", obj.stamp, ns + "_closest_object_velocity", 0, + visualization_msgs::msg::Marker::TEXT_VIEW_FACING, + tier4_autoware_utils::createMarkerScale(0.0, 0.0, 0.7), color); + closest_object_velocity_marker_array.pose.position = obj.position; + const auto ego_velocity = current_velocity_ptr_->longitudinal_velocity; + closest_object_velocity_marker_array.text = + "Object velocity: " + std::to_string(obj.velocity) + " [m/s]\n"; + closest_object_velocity_marker_array.text += + "Object relative velocity to ego: " + std::to_string(obj.velocity - ego_velocity) + " [m/s]"; + debug_markers.markers.push_back(closest_object_velocity_marker_array); + } } void AEB::addCollisionMarker(const ObjectData & data, MarkerArray & debug_markers) diff --git a/control/control_performance_analysis/src/control_performance_analysis_core.cpp b/control/control_performance_analysis/src/control_performance_analysis_core.cpp index 1ceef81e10c56..f4ed125956bfa 100644 --- a/control/control_performance_analysis/src/control_performance_analysis_core.cpp +++ b/control/control_performance_analysis/src/control_performance_analysis_core.cpp @@ -401,7 +401,7 @@ std::pair ControlPerformanceAnalysisCore::calculateClosestPose() if ( !interpolated_pose_ptr_ || !interpolated_velocity_ptr_ || !interpolated_acceleration_ptr_ || !interpolated_steering_angle_ptr_) { - std::make_pair(false, interp_point.pose); + return std::make_pair(false, interp_point.pose); } return std::make_pair(true, interp_point.pose); diff --git a/control/lane_departure_checker/README.md b/control/lane_departure_checker/README.md index 67b770aefb3d2..4a6592a103f2f 100644 --- a/control/lane_departure_checker/README.md +++ b/control/lane_departure_checker/README.md @@ -93,6 +93,7 @@ This package includes the following features: | Name | Type | Description | Default value | | :------------------------- | :----- | :--------------------------------------------------------------------------------- | :------------ | | footprint_margin_scale | double | Coefficient for expanding footprint margin. Multiplied by 1 standard deviation. | 1.0 | +| footprint_extra_margin | double | Coefficient for expanding footprint margin. When checking for lane departure | 0.0 | | resample_interval | double | Minimum Euclidean distance between points when resample trajectory.[m] | 0.3 | | max_deceleration | double | Maximum deceleration when calculating braking distance. | 2.8 | | delay_time | double | Delay time which took to actuate brake when calculating braking distance. [second] | 1.3 | diff --git a/control/lane_departure_checker/config/lane_departure_checker.param.yaml b/control/lane_departure_checker/config/lane_departure_checker.param.yaml index f0a8df21c425b..2724c28e2536a 100644 --- a/control/lane_departure_checker/config/lane_departure_checker.param.yaml +++ b/control/lane_departure_checker/config/lane_departure_checker.param.yaml @@ -17,6 +17,7 @@ # Core footprint_margin_scale: 1.0 + footprint_extra_margin: 0.0 resample_interval: 0.3 max_deceleration: 2.8 delay_time: 1.3 diff --git a/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp b/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp index c658cf4497973..b95c0a4b26e5c 100644 --- a/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp +++ b/control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp @@ -60,6 +60,7 @@ typedef boost::geometry::index::rtree LaneDepartureChecker::createVehicleFootprints( const PathWithLaneId & path) const { // Create vehicle footprint in base_link coordinate - const auto local_vehicle_footprint = vehicle_info_ptr_->createFootprint(); + const auto local_vehicle_footprint = + vehicle_info_ptr_->createFootprint(param_.footprint_extra_margin); // Create vehicle footprint on each Path point std::vector vehicle_footprints; diff --git a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp index 06d11133920f4..4d6c86990c399 100644 --- a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp +++ b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp @@ -150,6 +150,7 @@ LaneDepartureCheckerNode::LaneDepartureCheckerNode(const rclcpp::NodeOptions & o // Core Parameter param_.footprint_margin_scale = declare_parameter("footprint_margin_scale"); + param_.footprint_extra_margin = declare_parameter("footprint_extra_margin"); param_.resample_interval = declare_parameter("resample_interval"); param_.max_deceleration = declare_parameter("max_deceleration"); param_.delay_time = declare_parameter("delay_time"); @@ -403,6 +404,7 @@ rcl_interfaces::msg::SetParametersResult LaneDepartureCheckerNode::onParameter( // Core update_param(parameters, "footprint_margin_scale", param_.footprint_margin_scale); + update_param(parameters, "footprint_extra_margin", param_.footprint_extra_margin); update_param(parameters, "resample_interval", param_.resample_interval); update_param(parameters, "max_deceleration", param_.max_deceleration); update_param(parameters, "delay_time", param_.delay_time); 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 0000000000000..0349948cf80dd Binary files /dev/null and b/control/smart_mpc_trajectory_follower/images/autoware_smart_mpc.png differ 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 0000000000000..3a96faa8dcba1 Binary files /dev/null and b/control/smart_mpc_trajectory_follower/images/lateral_error_nominal_model.png differ 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 0000000000000..3396b9e7dd444 Binary files /dev/null and b/control/smart_mpc_trajectory_follower/images/lateral_error_trained_model.png differ 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 0000000000000..039d35ae44f8e Binary files /dev/null and b/control/smart_mpc_trajectory_follower/images/proxima_logo.png differ 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 0000000000000..84e64dde20e17 Binary files /dev/null and b/control/smart_mpc_trajectory_follower/images/python_sim_lateral_error_nominal_model.png differ 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 0000000000000..481375fcf68b1 Binary files /dev/null and b/control/smart_mpc_trajectory_follower/images/python_sim_lateral_error_trained_model.png differ 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 0000000000000..1387776e1a046 Binary files /dev/null and b/control/smart_mpc_trajectory_follower/images/test_route.png differ 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/control/trajectory_follower_node/config/plot_juggler_trajectory_follower.xml b/control/trajectory_follower_node/config/plot_juggler_trajectory_follower.xml index 6956db84aff56..ab127c2d47b97 100644 --- a/control/trajectory_follower_node/config/plot_juggler_trajectory_follower.xml +++ b/control/trajectory_follower_node/config/plot_juggler_trajectory_follower.xml @@ -1,5 +1,5 @@ - + @@ -9,37 +9,37 @@ - + - + - + - + - + - + - + @@ -50,12 +50,12 @@ - + - + @@ -66,12 +66,12 @@ - + - + @@ -84,22 +84,22 @@ - + - + - + - + @@ -110,12 +110,12 @@ - + - + @@ -141,52 +141,52 @@ - + - + - + - + - + - + - + - + - + - + @@ -197,7 +197,7 @@ - + @@ -209,22 +209,22 @@ - + - + - + - + @@ -241,33 +241,42 @@ - + - + + - + + + + - + + - - - - - - + + + + - - + + + + + + + + - + diff --git a/control/vehicle_cmd_gate/src/vehicle_cmd_filter.cpp b/control/vehicle_cmd_gate/src/vehicle_cmd_filter.cpp index 4431534a76a5e..b289365b46b3b 100644 --- a/control/vehicle_cmd_gate/src/vehicle_cmd_filter.cpp +++ b/control/vehicle_cmd_gate/src/vehicle_cmd_filter.cpp @@ -90,6 +90,11 @@ void VehicleCmdFilter::setParam(const VehicleCmdFilterParam & p) } } +VehicleCmdFilterParam VehicleCmdFilter::getParam() const +{ + return param_; +} + void VehicleCmdFilter::limitLongitudinalWithVel(AckermannControlCommand & input) const { input.longitudinal.speed = std::max( diff --git a/control/vehicle_cmd_gate/src/vehicle_cmd_filter.hpp b/control/vehicle_cmd_gate/src/vehicle_cmd_filter.hpp index cf7a1f627a68a..e71fb405beda1 100644 --- a/control/vehicle_cmd_gate/src/vehicle_cmd_filter.hpp +++ b/control/vehicle_cmd_gate/src/vehicle_cmd_filter.hpp @@ -58,6 +58,7 @@ class VehicleCmdFilter void setActualSteerDiffLim(LimitArray v); void setCurrentSpeed(double v) { current_speed_ = v; } void setParam(const VehicleCmdFilterParam & p); + VehicleCmdFilterParam getParam() const; void setPrevCmd(const AckermannControlCommand & v) { prev_cmd_ = v; } void limitLongitudinalWithVel(AckermannControlCommand & input) const; diff --git a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp index 27592b9405fc5..ffd452db0337c 100644 --- a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp +++ b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp @@ -15,6 +15,7 @@ #include "vehicle_cmd_gate.hpp" #include "marker_helper.hpp" +#include "tier4_autoware_utils/ros/update_param.hpp" #include #include @@ -244,6 +245,76 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options) logger_configure_ = std::make_unique(this); published_time_publisher_ = std::make_unique(this); + + // Parameter Callback + set_param_res_ = + this->add_on_set_parameters_callback(std::bind(&VehicleCmdGate::onParameter, this, _1)); +} + +rcl_interfaces::msg::SetParametersResult VehicleCmdGate::onParameter( + const std::vector & parameters) +{ + using tier4_autoware_utils::updateParam; + // Parameter + updateParam(parameters, "use_emergency_handling", use_emergency_handling_); + updateParam( + parameters, "check_external_emergency_heartbeat", check_external_emergency_heartbeat_); + updateParam( + parameters, "system_emergency_heartbeat_timeout", system_emergency_heartbeat_timeout_); + updateParam( + parameters, "external_emergency_stop_heartbeat_timeout", + external_emergency_stop_heartbeat_timeout_); + updateParam(parameters, "stop_hold_acceleration", stop_hold_acceleration_); + updateParam(parameters, "emergency_acceleration", emergency_acceleration_); + updateParam( + parameters, "moderate_stop_service_acceleration", moderate_stop_service_acceleration_); + updateParam(parameters, "stop_check_duration", stop_check_duration_); + updateParam(parameters, "enable_cmd_limit_filter", enable_cmd_limit_filter_); + updateParam( + parameters, "filter_activated_count_threshold", filter_activated_count_threshold_); + updateParam( + parameters, "filter_activated_velocity_threshold", filter_activated_velocity_threshold_); + + // Vehicle Parameter + const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); + { + VehicleCmdFilterParam p = filter_.getParam(); + p.wheel_base = vehicle_info.wheel_base_m; + updateParam(parameters, "nominal.vel_lim", p.vel_lim); + updateParam>( + parameters, "nominal.reference_speed_points", p.reference_speed_points); + updateParam>(parameters, "nominal.steer_lim", p.steer_lim); + updateParam>(parameters, "nominal.steer_rate_lim", p.steer_rate_lim); + updateParam>(parameters, "nominal.lon_acc_lim", p.lon_acc_lim); + updateParam>(parameters, "nominal.lon_jerk_lim", p.lon_jerk_lim); + updateParam>(parameters, "nominal.lat_acc_lim", p.lat_acc_lim); + updateParam>(parameters, "nominal.lat_jerk_lim", p.lat_jerk_lim); + updateParam>( + parameters, "nominal.actual_steer_diff_lim", p.actual_steer_diff_lim); + filter_.setParam(p); + } + + { + VehicleCmdFilterParam p = filter_on_transition_.getParam(); + p.wheel_base = vehicle_info.wheel_base_m; + updateParam(parameters, "on_transition.vel_lim", p.vel_lim); + updateParam>( + parameters, "on_transition.reference_speed_points", p.reference_speed_points); + updateParam>(parameters, "on_transition.steer_lim", p.steer_lim); + updateParam>(parameters, "on_transition.steer_rate_lim", p.steer_rate_lim); + updateParam>(parameters, "on_transition.lon_acc_lim", p.lon_acc_lim); + updateParam>(parameters, "on_transition.lon_jerk_lim", p.lon_jerk_lim); + updateParam>(parameters, "on_transition.lat_acc_lim", p.lat_acc_lim); + updateParam>(parameters, "on_transition.lat_jerk_lim", p.lat_jerk_lim); + updateParam>( + parameters, "on_transition.actual_steer_diff_lim", p.actual_steer_diff_lim); + filter_on_transition_.setParam(p); + } + + rcl_interfaces::msg::SetParametersResult result; + result.successful = true; + result.reason = "success"; + return result; } bool VehicleCmdGate::isHeartbeatTimeout( diff --git a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp index 1907cf123632f..85bc183361b94 100644 --- a/control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp +++ b/control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp @@ -49,6 +49,7 @@ #include #include +#include namespace vehicle_cmd_gate { @@ -111,7 +112,10 @@ class VehicleCmdGate : public rclcpp::Node rclcpp::Publisher::SharedPtr filter_activated_marker_pub_; rclcpp::Publisher::SharedPtr filter_activated_marker_raw_pub_; rclcpp::Publisher::SharedPtr filter_activated_flag_pub_; - + // Parameter callback + OnSetParametersCallbackHandle::SharedPtr set_param_res_; + rcl_interfaces::msg::SetParametersResult onParameter( + const std::vector & parameters); // Subscription rclcpp::Subscription::SharedPtr external_emergency_stop_heartbeat_sub_; rclcpp::Subscription::SharedPtr gate_mode_sub_; 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/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/param/perception_online_evaluator.defaults.yaml b/evaluator/perception_online_evaluator/param/perception_online_evaluator.defaults.yaml index 807f247807d98..16d4b6fe458cd 100644 --- a/evaluator/perception_online_evaluator/param/perception_online_evaluator.defaults.yaml +++ b/evaluator/perception_online_evaluator/param/perception_online_evaluator.defaults.yaml @@ -13,7 +13,7 @@ prediction_time_horizons: [1.0, 2.0, 3.0, 5.0] stopped_velocity_threshold: 1.0 - detection_radius_list: [50.0, 100.0, 150.0, 200.0] + detection_radius_list: [20.0, 40.0, 60.0, 80.0, 100.0, 120.0, 140.0, 160.0, 180.0, 200.0] detection_height_list: [10.0] detection_count_purge_seconds: 36000.0 objects_count_window_seconds: 1.0 diff --git a/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp b/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp index eed3206d48890..047d278334eb1 100644 --- a/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp +++ b/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp @@ -68,7 +68,7 @@ void DetectionCounter::addObjects( } const auto timestamp = objects.header.stamp; - unique_timestamps_.insert(timestamp).second; + unique_timestamps_.insert(timestamp); for (const auto & object : objects.objects) { const auto uuid = toHexString(object.object_id); @@ -119,7 +119,7 @@ void DetectionCounter::updateDetectionMap( const std::string uuid, const std::uint8_t classification, const std::string & range, const rclcpp::Time & timestamp) { - seen_uuids_[classification][range].insert(uuid).second; + seen_uuids_[classification][range].insert(uuid); // Record the detection time for averaging time_series_counts_[classification][range].push_back(timestamp); 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/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 6a67573717ae1..0000000000000 Binary files a/evaluator/tier4_metrics_rviz_plugin/icons/classes/MetricsVisualizePanel.png and /dev/null differ 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/launch/tier4_control_launch/launch/control.launch.py b/launch/tier4_control_launch/launch/control.launch.py index a63e7f547fef1..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,21 +330,57 @@ 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( + 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 +407,7 @@ def launch_setup(context, *args, **kwargs): obstacle_collision_checker_loader, autonomous_emergency_braking_loader, predicted_path_checker_loader, + control_evaluator_loader, ] ) @@ -391,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(): @@ -430,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", 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 diff --git a/launch/tier4_localization_launch/launch/pose_twist_estimator/ndt_scan_matcher.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_estimator/ndt_scan_matcher.launch.xml index 686e6d6cf12bc..ef3522b215227 100644 --- a/launch/tier4_localization_launch/launch/pose_twist_estimator/ndt_scan_matcher.launch.xml +++ b/launch/tier4_localization_launch/launch/pose_twist_estimator/ndt_scan_matcher.launch.xml @@ -1,5 +1,6 @@ + @@ -8,7 +9,7 @@ - + diff --git a/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml index c09443be8cab6..fa6bce0e38e55 100644 --- a/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml +++ b/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml @@ -1,5 +1,6 @@ + @@ -29,7 +30,20 @@ - + + + + + + + + + + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml index ddcbbbaeae107..6294df64279a5 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml @@ -8,6 +8,7 @@ + @@ -82,8 +83,9 @@ - - + + + @@ -207,9 +209,19 @@ + - + + + + + + + + + + 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 bc501f9b22aad..274b39be681b8 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 @@ -44,7 +44,8 @@ - + + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/pointcloud_map_filter.launch.py b/launch/tier4_perception_launch/launch/object_recognition/detection/pointcloud_map_filter.launch.py index a5af24595c593..5fa71cd1aa0e9 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/pointcloud_map_filter.launch.py +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/pointcloud_map_filter.launch.py @@ -85,7 +85,7 @@ def create_compare_map_pipeline(self): components.append( ComposableNode( package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::ApproximateDownsampleFilterComponent", + plugin="pointcloud_preprocessor::VoxelGridDownsampleFilterComponent", name="voxel_grid_downsample_filter", remappings=[ ("input", LaunchConfiguration("input_topic")), diff --git a/launch/tier4_perception_launch/launch/object_recognition/tracking/tracking.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/tracking/tracking.launch.xml index fed268084792a..cf11c65ac805c 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/tracking/tracking.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/tracking/tracking.launch.xml @@ -17,6 +17,7 @@ + @@ -26,6 +27,7 @@ + diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index f5df9cc4214c5..3ce78e3b29f29 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -22,6 +22,7 @@ + @@ -77,6 +78,7 @@ + + + + + + + + + + + + + + + + + + + + + + + + @@ -132,7 +157,7 @@ - + @@ -141,7 +166,7 @@ - + @@ -161,7 +186,7 @@ - + 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/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..51f0a32284626 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 @@ -7,9 +7,9 @@ - + - + @@ -42,13 +42,13 @@ - + - + @@ -220,7 +220,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..f8deccb188b71 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 @@ -2,6 +2,24 @@ + + + + + + + + + + @@ -91,12 +109,44 @@ - + - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/launch/tier4_planning_launch/package.xml b/launch/tier4_planning_launch/package.xml index 950ef67865a85..9d39c397f9417 100644 --- a/launch/tier4_planning_launch/package.xml +++ b/launch/tier4_planning_launch/package.xml @@ -57,8 +57,9 @@ ament_cmake_auto autoware_cmake + autoware_behavior_velocity_planner + autoware_remaining_distance_time_calculator behavior_path_planner - behavior_velocity_planner costmap_generator external_cmd_selector external_velocity_limit_selector diff --git a/launch/tier4_system_launch/launch/system.launch.xml b/launch/tier4_system_launch/launch/system.launch.xml index a1bbfc883de7c..6253dce864ddf 100644 --- a/launch/tier4_system_launch/launch/system.launch.xml +++ b/launch/tier4_system_launch/launch/system.launch.xml @@ -25,11 +25,11 @@ - - - - - + + + + + @@ -57,6 +57,13 @@ + + + + + + + @@ -70,8 +77,20 @@ + + + + + + + + + + + + - + @@ -85,52 +104,31 @@ - + + - - + + + - - - - - - - - - - + + + - + - - - - - - - - - - - - - - - - diff --git a/localization/autoware_pose_covariance_modifier/CMakeLists.txt b/localization/autoware_pose_covariance_modifier/CMakeLists.txt new file mode 100644 index 0000000000000..192434cc588d5 --- /dev/null +++ b/localization/autoware_pose_covariance_modifier/CMakeLists.txt @@ -0,0 +1,19 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_pose_covariance_modifier) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/pose_covariance_modifier.cpp +) + +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "autoware::pose_covariance_modifier::PoseCovarianceModifierNode" + EXECUTABLE ${PROJECT_NAME}_node +) + +ament_auto_package(INSTALL_TO_SHARE + config + launch +) diff --git a/localization/autoware_pose_covariance_modifier/README.md b/localization/autoware_pose_covariance_modifier/README.md new file mode 100644 index 0000000000000..392df9caca6eb --- /dev/null +++ b/localization/autoware_pose_covariance_modifier/README.md @@ -0,0 +1,213 @@ +# Autoware Pose Covariance Modifier Node + +## Purpose + +This package makes it possible to use GNSS and NDT poses together in real time localization. + +## Function + +This package takes in GNSS (Global Navigation Satellite System) +and NDT (Normal Distribution Transform) poses with covariances. + +It outputs a single pose with covariance: + +- Directly the GNSS pose and its covariance. +- Directly the NDT pose and its covariance. +- Both GNSS and NDT poses with modified covariances. + +> - This package doesn't modify the pose information it receives. +> - It only modifies NDT covariance values under certain conditions. + +## Assumptions + +- The NDT matcher provides a pose with a fixed covariance. +- The NDT matcher is unable to provide a dynamic, reliable covariance value. + +## Requirements + +- The GNSS/INS module must provide standard deviation values (its error / RMSE) for the position and orientation. +- It probably needs RTK support to provide accurate position and orientation information. +- You need to have a geo-referenced map. +- GNSS/INS module and the base_link frame must be calibrated well enough. +- In an environment where GNSS/INS and NDT systems work well, the `base_link` poses from both systems should be close to + each other. + +## Description + +GNSS and NDT nodes provide the pose with covariance data utilized in an Extended Kalman Filter (EKF). + +Accurate covariance values are crucial for the effectiveness of the EKF in estimating the state. + +The GNSS system generates reliable standard deviation values, which can be transformed into covariance measures. + +But we currently don't have a reliable way to determine the covariance values for the NDT poses. +And the NDT matching system in Autoware outputs poses with preset covariance values. + +For this reason, this package is designed to manage the selection of the pose source, +based on the standard deviation values provided by the GNSS system. + +It also tunes the covariance values of the NDT poses, based on the GNSS standard deviation values. + +## Flowcharts + +### Without this package + +Only NDT pose is used in localization. GNSS pose is only used for initialization. + +```mermaid +graph TD + ndt_scan_matcher["ndt_scan_matcher"] --> |"/localization/pose_estimator/pose_with_covariance"| ekf_localizer["ekf_localizer"] + +classDef cl_node fill:#FFF2CC,stroke-width:3px,stroke:#D6B656; + +class ndt_scan_matcher cl_node; +class ekf_localizer cl_node; +``` + +### With this package + +Both NDT and GNSS poses are used in localization, depending on the standard deviation values coming from the GNSS +system. + +Here is a flowchart depicting the process and the predefined thresholds: + +```mermaid +graph TD + gnss_poser["gnss_poser"] --> |"/sensing/gnss/\npose_with_covariance"| pose_covariance_modifier_node + ndt_scan_matcher["ndt_scan_matcher"] --> |"/localization/pose_estimator/ndt_scan_matcher/\npose_with_covariance"| pose_covariance_modifier_node + + subgraph pose_covariance_modifier_node ["Pose Covariance Modifier Node"] + pc1{{"gnss_pose_yaw\nstddev"}} + pc1 -->|"<= 0.3 rad"| pc2{{"gnss_pose_z\nstddev"}} + pc2 -->|"<= 0.1 m"| pc3{{"gnss_pose_xy\nstddev"}} + pc2 -->|"> 0.1 m"| ndt_pose("NDT Pose") + pc3 -->|"<= 0.1 m"| gnss_pose("GNSS Pose") + pc3 -->|"0.1 m < x <= 0.2 m"| gnss_ndt_pose("`Both GNSS and NDT Pose + (_with modified covariance_)`") + pc3 -->|"> 0.2 m"| ndt_pose + pc1 -->|"> 0.3 rad"| ndt_pose + end + + pose_covariance_modifier_node -->|"/localization/pose_estimator/pose_with_covariance"| ekf_localizer["ekf_localizer"] + +classDef cl_node fill:#FFF2CC,stroke-width:3px,stroke:#D6B656; +classDef cl_conditional fill:#FFE6CC,stroke-width:3px,stroke:#D79B00; +classDef cl_output fill:#D5E8D4,stroke-width:3px,stroke:#82B366; + +class gnss_poser cl_node; +class ndt_scan_matcher cl_node; +class ekf_localizer cl_node; +class pose_covariance_modifier_node cl_node; + +class pc1 cl_conditional; +class pc2 cl_conditional; +class pc3 cl_conditional; + +class ndt_pose cl_output; +class gnss_pose cl_output; +class gnss_ndt_pose cl_output; +``` + +## How to use this package + +> **This package is disabled by default in Autoware, you need to manually enable it.** + +To enable this package, you need to change the `use_autoware_pose_covariance_modifier` parameter to `true` within +the [pose_twist_estimator.launch.xml](../../launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml#L3). + +### Without this condition (default) + +- The output of the [ndt_scan_matcher](../../localization/ndt_scan_matcher) is directly sent + to [ekf_localizer](../../localization/ekf_localizer). + - It has a preset covariance value. + - **topic name:** `/localization/pose_estimator/pose_with_covariance` +- The GNSS pose does not enter the ekf_localizer. +- This node does not launch. + +### With this condition + +- The output of the [ndt_scan_matcher](../../localization/ndt_scan_matcher) is renamed + - **from:** `/localization/pose_estimator/pose_with_covariance`. + - **to:** `/localization/pose_estimator/ndt_scan_matcher/pose_with_covariance`. +- The `ndt_scan_matcher` output enters the `autoware_pose_covariance_modifier`. +- The output of this package goes to [ekf_localizer](../../localization/ekf_localizer) with: + - **topic name:** `/localization/pose_estimator/pose_with_covariance`. + +## Node + +### Subscribed topics + +| Name | Type | Description | +| -------------------------------- | ----------------------------------------------- | ---------------------- | +| `input_gnss_pose_with_cov_topic` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Input GNSS pose topic. | +| `input_ndt_pose_with_cov_topic` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Input NDT pose topic. | + +### Published topics + +| Name | Type | Description | +| ----------------------------------- | ----------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------- | +| `output_pose_with_covariance_topic` | `geometry_msgs::msg::PoseWithCovarianceStamped` | Output pose topic. This topic is used by the ekf_localizer package. | +| `selected_pose_type` | `std_msgs::msg::String` | Declares which pose sources are used in the output of this package | +| `output/ndt_position_stddev` | `std_msgs::msg::Float64` | Output pose ndt average standard deviation in position xy. It is published only when the enable_debug_topics is true. | +| `output/gnss_position_stddev` | `std_msgs::msg::Float64` | Output pose gnss average standard deviation in position xy. It is published only when the enable_debug_topics is true. | + +### Parameters + +The parameters are set +in [config/pose_covariance_modifier.param.yaml](config/pose_covariance_modifier.param.yaml) . + +{{ json_to_markdown(" +localization/autoware_pose_covariance_modifier/schema/pose_covariance_modifier.schema.json") }} + +## FAQ + +### How are varying frequency rates handled? + +The GNSS and NDT pose topics may have different frequencies. +The GNSS pose topic may have a higher frequency than the NDT. + +Let's assume that the inputs have the following frequencies: + +| Source | Frequency | +| ------ | --------- | +| GNSS | 200 Hz | +| NDT | 10 Hz | + +This package publishes the output poses as they come in, depending on the mode. + +End result: + +| Mode | Output Freq | +| ---------- | ----------- | +| GNSS Only | 200 Hz | +| GNSS + NDT | 210 Hz | +| NDT Only | 10 Hz | + +### How and when are the NDT covariance values overwritten? + +| Mode | Outputs, Covariance | +| ---------- | ------------------------------------------- | +| GNSS Only | GNSS, Unmodified | +| GNSS + NDT | **GNSS:** Unmodified, **NDT:** Interpolated | +| NDT Only | NDT, Unmodified | + +NDT covariance values overwritten only for the `GNSS + NDT` mode. + +This enables a smooth transition between `GNSS Only` and `NDT Only` modes. + +In this mode, both NDT and GNSS poses are published from this node. + +#### NDT covariance calculation + +As the `gnss_std_dev` increases within its bounds, `ndt_std_dev` should proportionally decrease within its own bounds. + +To achieve this, we first linearly interpolate: + +- Base value: `gnss_std_dev` +- Base range: [`threshold_gnss_stddev_xy_bound_lower`, `threshold_gnss_stddev_xy_bound_upper`] +- Target range: [`ndt_std_dev_bound_lower`, `ndt_std_dev_bound_upper`] +- Target value: `ndt_std_dev_target` + +- Final value = `ndt_std_dev_bound_lower` + `ndt_std_dev_bound_upper` - `ndt_std_dev_target` (to get the inverse) + +range to range lerp animation diff --git a/localization/autoware_pose_covariance_modifier/config/pose_covariance_modifier.param.yaml b/localization/autoware_pose_covariance_modifier/config/pose_covariance_modifier.param.yaml new file mode 100644 index 0000000000000..7d63b3b6de4cb --- /dev/null +++ b/localization/autoware_pose_covariance_modifier/config/pose_covariance_modifier.param.yaml @@ -0,0 +1,24 @@ +/**: + ros__parameters: + # If GNSS yaw standard deviation values are larger than this, trust only NDT + threshold_gnss_stddev_yaw_deg_max: 0.3 + + # If GNSS position Z standard deviation values are larger than this, trust only NDT + threshold_gnss_stddev_z_max: 0.1 + + # If GNSS position XY standard deviation values are lower than this, trust only GNSS + threshold_gnss_stddev_xy_bound_lower: 0.1 + + # If GNSS position XY standard deviation values are higher than this, trust only NDT + threshold_gnss_stddev_xy_bound_upper: 0.25 + + # Lower bound value for standard deviation of NDT positions (x, y, z) when used with GNSS + ndt_std_dev_bound_lower: 0.14 + + # Upper bound value for standard deviation of NDT positions (x, y, z) when used with GNSS + ndt_std_dev_bound_upper: 0.30 + + # If GNSS data is not received for this duration, trust only NDT + gnss_pose_timeout_sec: 1.0 + + enable_debug_topics: true diff --git a/localization/autoware_pose_covariance_modifier/doc/range_lerp.svg b/localization/autoware_pose_covariance_modifier/doc/range_lerp.svg new file mode 100644 index 0000000000000..747777b14de58 --- /dev/null +++ b/localization/autoware_pose_covariance_modifier/doc/range_lerp.svg @@ -0,0 +1,36 @@ + + + + + + + + + + + + +Base + + + + +Target + + + + 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) diff --git a/localization/ekf_localizer/CMakeLists.txt b/localization/ekf_localizer/CMakeLists.txt index 9944cbb84d97c..13e63ddf3c170 100644 --- a/localization/ekf_localizer/CMakeLists.txt +++ b/localization/ekf_localizer/CMakeLists.txt @@ -13,7 +13,7 @@ include_directories( ament_auto_find_build_dependencies() -ament_auto_add_library(ekf_localizer_lib SHARED +ament_auto_add_library(${PROJECT_NAME} SHARED src/ekf_localizer.cpp src/covariance.cpp src/diagnostics.cpp @@ -24,21 +24,20 @@ ament_auto_add_library(ekf_localizer_lib SHARED src/ekf_module.cpp ) -target_link_libraries(ekf_localizer_lib Eigen3::Eigen) - -ament_auto_add_executable(ekf_localizer src/ekf_localizer_node.cpp) - -target_compile_options(ekf_localizer PUBLIC -g -Wall -Wextra -Wpedantic -Werror) +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "EKFLocalizer" + EXECUTABLE ${PROJECT_NAME}_node + EXECUTOR SingleThreadedExecutor +) -target_link_libraries(ekf_localizer ekf_localizer_lib) -target_include_directories(ekf_localizer PUBLIC include) +target_link_libraries(${PROJECT_NAME} Eigen3::Eigen) function(add_testcase filepath) get_filename_component(filename ${filepath} NAME) string(REGEX REPLACE ".cpp" "" test_name ${filename}) ament_add_gtest(${test_name} ${filepath}) - target_link_libraries("${test_name}" ekf_localizer_lib) + target_link_libraries("${test_name}" ${PROJECT_NAME}) ament_target_dependencies(${test_name} ${${PROJECT_NAME}_FOUND_BUILD_DEPENDS}) endfunction() diff --git a/localization/ekf_localizer/README.md b/localization/ekf_localizer/README.md index 1b09420f5047d..b91282015732e 100644 --- a/localization/ekf_localizer/README.md +++ b/localization/ekf_localizer/README.md @@ -130,6 +130,26 @@ Increasing the number will improve the smoothness of the estimation, but may hav - `proc_stddev_yaw_c` : This parameter describes the correlation between the yaw and yaw rate. A large value means the change in yaw does not correlate to the estimated yaw rate. If this is set to 0, it means the change in estimated yaw is equal to yaw rate. Usually, this should be set to 0. - `proc_stddev_yaw_bias_c` : This parameter is the standard deviation for the rate of change in yaw bias. In most cases, yaw bias is constant, so it can be very small, but must be non-zero. +### 3. Tune gate parameters + +EKF performs gating using Mahalanobis distance before updating by observation. The gate size is determined by the `pose_gate_dist` parameter and the `twist_gate_dist`. If the Mahalanobis distance is larger than this value, the observation is ignored. + +This gating process is based on a statistical test using the chi-square distribution. As modeled, we assume that the Mahalanobis distance follows a chi-square distribution with 3 degrees of freedom for pose and 2 degrees of freedom for twist. + +Currently, the accuracy of covariance estimation itself is not very good, so it is recommended to set the significance level to a very small value to reduce rejection due to false positives. + +| Significance level | Threshold for 2 dof | Threshold for 3 dof | +| ------------------ | ------------------- | ------------------- | +| $10 ^ {-2}$ | 9.21 | 11.3 | +| $10 ^ {-3}$ | 13.8 | 16.3 | +| $10 ^ {-4}$ | 18.4 | 21.1 | +| $10 ^ {-5}$ | 23.0 | 25.9 | +| $10 ^ {-6}$ | 27.6 | 30.7 | +| $10 ^ {-7}$ | 32.2 | 35.4 | +| $10 ^ {-8}$ | 36.8 | 40.1 | +| $10 ^ {-9}$ | 41.4 | 44.8 | +| $10 ^ {-10}$ | 46.1 | 49.5 | + ## Kalman Filter Model ### kinematics model in update function diff --git a/localization/ekf_localizer/config/ekf_localizer.param.yaml b/localization/ekf_localizer/config/ekf_localizer.param.yaml index 4cc71e0904ca8..19bfd2d498b68 100644 --- a/localization/ekf_localizer/config/ekf_localizer.param.yaml +++ b/localization/ekf_localizer/config/ekf_localizer.param.yaml @@ -13,13 +13,13 @@ pose_additional_delay: 0.0 pose_measure_uncertainty_time: 0.01 pose_smoothing_steps: 5 - pose_gate_dist: 10000.0 + pose_gate_dist: 49.5 # corresponds to significance level = 10^-10 twist_measurement: # for twist measurement twist_additional_delay: 0.0 twist_smoothing_steps: 2 - twist_gate_dist: 10000.0 + twist_gate_dist: 46.1 # corresponds to significance level = 10^-10 process_noise: # for process model diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp index 6925e8b63c66b..8ed925c1bc228 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp @@ -102,7 +102,7 @@ class Simple1DFilter class EKFLocalizer : public rclcpp::Node { public: - EKFLocalizer(const std::string & node_name, const rclcpp::NodeOptions & options); + explicit EKFLocalizer(const rclcpp::NodeOptions & options); private: const std::shared_ptr warning_; diff --git a/localization/ekf_localizer/launch/ekf_localizer.launch.xml b/localization/ekf_localizer/launch/ekf_localizer.launch.xml index b6a1bd06185c2..3c66fabe34650 100644 --- a/localization/ekf_localizer/launch/ekf_localizer.launch.xml +++ b/localization/ekf_localizer/launch/ekf_localizer.launch.xml @@ -17,7 +17,7 @@ - + diff --git a/localization/ekf_localizer/media/ekf_diagnostics.png b/localization/ekf_localizer/media/ekf_diagnostics.png index 2580d6d973290..16de42ac2d85a 100644 Binary files a/localization/ekf_localizer/media/ekf_diagnostics.png and b/localization/ekf_localizer/media/ekf_diagnostics.png differ diff --git a/localization/ekf_localizer/package.xml b/localization/ekf_localizer/package.xml index e9d756e547f26..dad1b0e730711 100644 --- a/localization/ekf_localizer/package.xml +++ b/localization/ekf_localizer/package.xml @@ -29,6 +29,7 @@ kalman_filter nav_msgs rclcpp + rclcpp_components std_srvs tf2 tf2_ros diff --git a/localization/ekf_localizer/schema/sub/pose_measurement.sub_schema.json b/localization/ekf_localizer/schema/sub/pose_measurement.sub_schema.json index 8b931d5f68d12..d2bc313d4dc75 100644 --- a/localization/ekf_localizer/schema/sub/pose_measurement.sub_schema.json +++ b/localization/ekf_localizer/schema/sub/pose_measurement.sub_schema.json @@ -23,7 +23,7 @@ "pose_gate_dist": { "type": "number", "description": "Limit of Mahalanobis distance used for outliers detection", - "default": 10000.0 + "default": 49.5 } }, "required": [ diff --git a/localization/ekf_localizer/schema/sub/twist_measurement.sub_schema.json b/localization/ekf_localizer/schema/sub/twist_measurement.sub_schema.json index 727830a90a288..7b80133cb38aa 100644 --- a/localization/ekf_localizer/schema/sub/twist_measurement.sub_schema.json +++ b/localization/ekf_localizer/schema/sub/twist_measurement.sub_schema.json @@ -18,7 +18,7 @@ "twist_gate_dist": { "type": "number", "description": "Limit of Mahalanobis distance used for outliers detection", - "default": 10000.0 + "default": 46.1 } }, "required": ["twist_additional_delay", "twist_smoothing_steps", "twist_gate_dist"], diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index f77481d45a534..687e812679574 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -40,8 +40,8 @@ using std::placeholders::_1; -EKFLocalizer::EKFLocalizer(const std::string & node_name, const rclcpp::NodeOptions & node_options) -: rclcpp::Node(node_name, node_options), +EKFLocalizer::EKFLocalizer(const rclcpp::NodeOptions & node_options) +: rclcpp::Node("ekf_localizer", node_options), warning_(std::make_shared(this)), params_(this), ekf_dt_(params_.ekf_dt), @@ -479,3 +479,6 @@ void EKFLocalizer::serviceTriggerNode( res->success = true; return; } + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(EKFLocalizer) diff --git a/localization/ekf_localizer/src/ekf_localizer_node.cpp b/localization/ekf_localizer/src/ekf_localizer_node.cpp deleted file mode 100644 index 0f75f19c5d50b..0000000000000 --- a/localization/ekf_localizer/src/ekf_localizer_node.cpp +++ /dev/null @@ -1,28 +0,0 @@ -// Copyright 2018-2019 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 "ekf_localizer/ekf_localizer.hpp" - -#include - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - rclcpp::NodeOptions node_options; - auto node = std::make_shared("ekf_localizer", node_options); - - rclcpp::spin(node); - - return 0; -} diff --git a/localization/geo_pose_projector/CMakeLists.txt b/localization/geo_pose_projector/CMakeLists.txt index 6e2cdf32fb6c5..f274e7d23dbab 100644 --- a/localization/geo_pose_projector/CMakeLists.txt +++ b/localization/geo_pose_projector/CMakeLists.txt @@ -4,11 +4,15 @@ project(geo_pose_projector) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_executable(geo_pose_projector - src/geo_pose_projector_node.cpp +ament_auto_add_library(${PROJECT_NAME} SHARED src/geo_pose_projector.cpp ) -ament_target_dependencies(geo_pose_projector) + +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "GeoPoseProjector" + EXECUTABLE ${PROJECT_NAME}_node + EXECUTOR SingleThreadedExecutor +) ament_auto_package( INSTALL_TO_SHARE diff --git a/localization/geo_pose_projector/launch/geo_pose_projector.launch.xml b/localization/geo_pose_projector/launch/geo_pose_projector.launch.xml index d840add1ed1c7..de6785a016858 100644 --- a/localization/geo_pose_projector/launch/geo_pose_projector.launch.xml +++ b/localization/geo_pose_projector/launch/geo_pose_projector.launch.xml @@ -4,7 +4,7 @@ - + diff --git a/localization/geo_pose_projector/package.xml b/localization/geo_pose_projector/package.xml index c0e2db59deb64..36b2aec8384ac 100644 --- a/localization/geo_pose_projector/package.xml +++ b/localization/geo_pose_projector/package.xml @@ -24,6 +24,7 @@ geography_utils geometry_msgs rclcpp + rclcpp_components tf2_geometry_msgs tf2_ros diff --git a/localization/geo_pose_projector/src/geo_pose_projector.cpp b/localization/geo_pose_projector/src/geo_pose_projector.cpp index d147888bb743b..80bb407958de2 100644 --- a/localization/geo_pose_projector/src/geo_pose_projector.cpp +++ b/localization/geo_pose_projector/src/geo_pose_projector.cpp @@ -25,8 +25,8 @@ #include -GeoPoseProjector::GeoPoseProjector() -: Node("geo_pose_projector"), publish_tf_(declare_parameter("publish_tf")) +GeoPoseProjector::GeoPoseProjector(const rclcpp::NodeOptions & options) +: rclcpp::Node("geo_pose_projector", options), publish_tf_(declare_parameter("publish_tf")) { // Subscribe to map_projector_info topic const auto adaptor = component_interface_utils::NodeAdaptor(this); @@ -102,3 +102,6 @@ void GeoPoseProjector::on_geo_pose(const GeoPoseWithCovariance::ConstSharedPtr m tf_broadcaster_->sendTransform(transform_stamped); } } + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(GeoPoseProjector) diff --git a/localization/geo_pose_projector/src/geo_pose_projector.hpp b/localization/geo_pose_projector/src/geo_pose_projector.hpp index b0611fec36984..738e805ef8101 100644 --- a/localization/geo_pose_projector/src/geo_pose_projector.hpp +++ b/localization/geo_pose_projector/src/geo_pose_projector.hpp @@ -36,7 +36,7 @@ class GeoPoseProjector : public rclcpp::Node using MapProjectorInfo = map_interface::MapProjectorInfo; public: - GeoPoseProjector(); + explicit GeoPoseProjector(const rclcpp::NodeOptions & options); private: void on_geo_pose(const GeoPoseWithCovariance::ConstSharedPtr msg); diff --git a/localization/geo_pose_projector/src/geo_pose_projector_node.cpp b/localization/geo_pose_projector/src/geo_pose_projector_node.cpp deleted file mode 100644 index 97367d6b9f774..0000000000000 --- a/localization/geo_pose_projector/src/geo_pose_projector_node.cpp +++ /dev/null @@ -1,29 +0,0 @@ -// Copyright 2023 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 "geo_pose_projector.hpp" - -#include - -#include - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - - rclcpp::spin(std::make_shared()); - rclcpp::shutdown(); - - return 0; -} diff --git a/localization/gyro_odometer/CMakeLists.txt b/localization/gyro_odometer/CMakeLists.txt index 57589837dd529..a832383ff4761 100644 --- a/localization/gyro_odometer/CMakeLists.txt +++ b/localization/gyro_odometer/CMakeLists.txt @@ -4,17 +4,12 @@ project(gyro_odometer) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_executable(${PROJECT_NAME} - src/gyro_odometer_node.cpp +ament_auto_add_library(${PROJECT_NAME} SHARED src/gyro_odometer_core.cpp ) target_link_libraries(${PROJECT_NAME} fmt) -ament_auto_add_library(gyro_odometer_node SHARED - src/gyro_odometer_core.cpp -) - if(BUILD_TESTING) ament_add_ros_isolated_gtest(test_gyro_odometer test/test_main.cpp @@ -25,10 +20,15 @@ if(BUILD_TESTING) rclcpp ) target_link_libraries(test_gyro_odometer - gyro_odometer_node + ${PROJECT_NAME} ) endif() +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "autoware::gyro_odometer::GyroOdometerNode" + EXECUTABLE ${PROJECT_NAME}_node + EXECUTOR SingleThreadedExecutor +) ament_auto_package(INSTALL_TO_SHARE launch diff --git a/localization/gyro_odometer/include/gyro_odometer/gyro_odometer_core.hpp b/localization/gyro_odometer/include/gyro_odometer/gyro_odometer_core.hpp index 3a6358e62c21a..2926589bd2da9 100644 --- a/localization/gyro_odometer/include/gyro_odometer/gyro_odometer_core.hpp +++ b/localization/gyro_odometer/include/gyro_odometer/gyro_odometer_core.hpp @@ -36,14 +36,17 @@ #include #include -class GyroOdometer : public rclcpp::Node +namespace autoware::gyro_odometer +{ + +class GyroOdometerNode : public rclcpp::Node { private: using COV_IDX = tier4_autoware_utils::xyz_covariance_index::XYZ_COV_IDX; public: - explicit GyroOdometer(const rclcpp::NodeOptions & options); - ~GyroOdometer(); + explicit GyroOdometerNode(const rclcpp::NodeOptions & node_options); + ~GyroOdometerNode(); private: void callbackVehicleTwist( @@ -75,4 +78,6 @@ class GyroOdometer : public rclcpp::Node std::deque gyro_queue_; }; +} // namespace autoware::gyro_odometer + #endif // GYRO_ODOMETER__GYRO_ODOMETER_CORE_HPP_ diff --git a/localization/gyro_odometer/launch/gyro_odometer.launch.xml b/localization/gyro_odometer/launch/gyro_odometer.launch.xml index 21aff3e10d26c..aed6050858fe1 100644 --- a/localization/gyro_odometer/launch/gyro_odometer.launch.xml +++ b/localization/gyro_odometer/launch/gyro_odometer.launch.xml @@ -11,7 +11,7 @@ - + diff --git a/localization/gyro_odometer/package.xml b/localization/gyro_odometer/package.xml index a0a982ddedc16..3c979eb69ac8a 100644 --- a/localization/gyro_odometer/package.xml +++ b/localization/gyro_odometer/package.xml @@ -19,14 +19,13 @@ fmt geometry_msgs + rclcpp + rclcpp_components sensor_msgs tf2 tf2_geometry_msgs tier4_autoware_utils - rclcpp - rclcpp_components - ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/localization/gyro_odometer/src/gyro_odometer_core.cpp b/localization/gyro_odometer/src/gyro_odometer_core.cpp index 5de0ecd7cdc0a..bda7af74b8489 100644 --- a/localization/gyro_odometer/src/gyro_odometer_core.cpp +++ b/localization/gyro_odometer/src/gyro_odometer_core.cpp @@ -14,6 +14,8 @@ #include "gyro_odometer/gyro_odometer_core.hpp" +#include + #ifdef ROS_DISTRO_GALACTIC #include #else @@ -25,6 +27,42 @@ #include #include +namespace autoware::gyro_odometer +{ + +GyroOdometerNode::GyroOdometerNode(const rclcpp::NodeOptions & node_options) +: Node("gyro_odometer", node_options), + output_frame_(declare_parameter("output_frame")), + message_timeout_sec_(declare_parameter("message_timeout_sec")), + vehicle_twist_arrived_(false), + imu_arrived_(false) +{ + transform_listener_ = std::make_shared(this); + logger_configure_ = std::make_unique(this); + + vehicle_twist_sub_ = create_subscription( + "vehicle/twist_with_covariance", rclcpp::QoS{100}, + std::bind(&GyroOdometerNode::callbackVehicleTwist, this, std::placeholders::_1)); + + imu_sub_ = create_subscription( + "imu", rclcpp::QoS{100}, + std::bind(&GyroOdometerNode::callbackImu, this, std::placeholders::_1)); + + twist_raw_pub_ = create_publisher("twist_raw", rclcpp::QoS{10}); + twist_with_covariance_raw_pub_ = create_publisher( + "twist_with_covariance_raw", rclcpp::QoS{10}); + + twist_pub_ = create_publisher("twist", rclcpp::QoS{10}); + twist_with_covariance_pub_ = create_publisher( + "twist_with_covariance", rclcpp::QoS{10}); + + // TODO(YamatoAndo) createTimer +} + +GyroOdometerNode::~GyroOdometerNode() +{ +} + std::array transformCovariance(const std::array & cov) { using COV_IDX = tier4_autoware_utils::xyz_covariance_index::XYZ_COV_IDX; @@ -100,39 +138,7 @@ geometry_msgs::msg::TwistWithCovarianceStamped concatGyroAndOdometer( return twist_with_cov; } -GyroOdometer::GyroOdometer(const rclcpp::NodeOptions & options) -: Node("gyro_odometer", options), - output_frame_(declare_parameter("output_frame")), - message_timeout_sec_(declare_parameter("message_timeout_sec")), - vehicle_twist_arrived_(false), - imu_arrived_(false) -{ - transform_listener_ = std::make_shared(this); - logger_configure_ = std::make_unique(this); - - vehicle_twist_sub_ = create_subscription( - "vehicle/twist_with_covariance", rclcpp::QoS{100}, - std::bind(&GyroOdometer::callbackVehicleTwist, this, std::placeholders::_1)); - - imu_sub_ = create_subscription( - "imu", rclcpp::QoS{100}, std::bind(&GyroOdometer::callbackImu, this, std::placeholders::_1)); - - twist_raw_pub_ = create_publisher("twist_raw", rclcpp::QoS{10}); - twist_with_covariance_raw_pub_ = create_publisher( - "twist_with_covariance_raw", rclcpp::QoS{10}); - - twist_pub_ = create_publisher("twist", rclcpp::QoS{10}); - twist_with_covariance_pub_ = create_publisher( - "twist_with_covariance", rclcpp::QoS{10}); - - // TODO(YamatoAndo) createTimer -} - -GyroOdometer::~GyroOdometer() -{ -} - -void GyroOdometer::callbackVehicleTwist( +void GyroOdometerNode::callbackVehicleTwist( const geometry_msgs::msg::TwistWithCovarianceStamped::ConstSharedPtr vehicle_twist_ptr) { vehicle_twist_arrived_ = true; @@ -173,7 +179,7 @@ void GyroOdometer::callbackVehicleTwist( gyro_queue_.clear(); } -void GyroOdometer::callbackImu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg_ptr) +void GyroOdometerNode::callbackImu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg_ptr) { imu_arrived_ = true; if (!vehicle_twist_arrived_) { @@ -241,7 +247,7 @@ void GyroOdometer::callbackImu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_m gyro_queue_.clear(); } -void GyroOdometer::publishData( +void GyroOdometerNode::publishData( const geometry_msgs::msg::TwistWithCovarianceStamped & twist_with_cov_raw) { geometry_msgs::msg::TwistStamped twist_raw; @@ -269,3 +275,8 @@ void GyroOdometer::publishData( twist_pub_->publish(twist); twist_with_covariance_pub_->publish(twist_with_covariance); } + +} // namespace autoware::gyro_odometer + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::gyro_odometer::GyroOdometerNode) diff --git a/localization/gyro_odometer/src/gyro_odometer_node.cpp b/localization/gyro_odometer/src/gyro_odometer_node.cpp deleted file mode 100644 index 5bb6241506fbe..0000000000000 --- a/localization/gyro_odometer/src/gyro_odometer_node.cpp +++ /dev/null @@ -1,30 +0,0 @@ -// Copyright 2015-2019 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 "gyro_odometer/gyro_odometer_core.hpp" - -#include - -#include - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - rclcpp::NodeOptions options; - auto node = std::make_shared(options); - rclcpp::spin(node); - rclcpp::shutdown(); - - return 0; -} diff --git a/localization/gyro_odometer/test/test_gyro_odometer_pubsub.cpp b/localization/gyro_odometer/test/test_gyro_odometer_pubsub.cpp index 7f6416fbdda16..b7849ef03bfc5 100644 --- a/localization/gyro_odometer/test/test_gyro_odometer_pubsub.cpp +++ b/localization/gyro_odometer/test/test_gyro_odometer_pubsub.cpp @@ -108,7 +108,8 @@ TEST(GyroOdometer, TestGyroOdometerWithImuAndVelocity) expected_output_twist.twist.twist.angular.y = input_imu.angular_velocity.y; expected_output_twist.twist.twist.angular.z = input_imu.angular_velocity.z; - auto gyro_odometer_node = std::make_shared(getNodeOptionsWithDefaultParams()); + auto gyro_odometer_node = + std::make_shared(getNodeOptionsWithDefaultParams()); auto imu_generator = std::make_shared(); auto velocity_generator = std::make_shared(); auto gyro_odometer_validator_node = std::make_shared(); @@ -135,7 +136,8 @@ TEST(GyroOdometer, TestGyroOdometerImuOnly) { Imu input_imu = generateSampleImu(); - auto gyro_odometer_node = std::make_shared(getNodeOptionsWithDefaultParams()); + auto gyro_odometer_node = + std::make_shared(getNodeOptionsWithDefaultParams()); auto imu_generator = std::make_shared(); auto gyro_odometer_validator_node = std::make_shared(); diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/CMakeLists.txt b/localization/landmark_based_localizer/ar_tag_based_localizer/CMakeLists.txt index d625064b8f6cb..a8435fa056847 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/CMakeLists.txt +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/CMakeLists.txt @@ -14,27 +14,33 @@ ament_auto_find_build_dependencies() find_package(OpenCV REQUIRED) -ament_auto_add_executable(ar_tag_based_localizer - src/main.cpp +ament_auto_add_library(${PROJECT_NAME} SHARED src/ar_tag_based_localizer.cpp ) -target_include_directories(ar_tag_based_localizer + +target_include_directories(${PROJECT_NAME} SYSTEM PUBLIC ${OpenCV_INCLUDE_DIRS} ) -target_link_libraries(ar_tag_based_localizer ${OpenCV_LIBRARIES}) +target_link_libraries(${PROJECT_NAME} ${OpenCV_LIBRARIES}) + +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "ArTagBasedLocalizer" + EXECUTABLE ${PROJECT_NAME}_node + EXECUTOR SingleThreadedExecutor +) if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) - ament_auto_add_gtest(test_ar_tag_based_localizer + ament_auto_add_gtest(test_${PROJECT_NAME} test/test.cpp src/ar_tag_based_localizer.cpp ) - target_include_directories(test_ar_tag_based_localizer + target_include_directories(test_${PROJECT_NAME} SYSTEM PUBLIC ${OpenCV_INCLUDE_DIRS} ) - target_link_libraries(test_ar_tag_based_localizer ${OpenCV_LIBRARIES}) + target_link_libraries(test_${PROJECT_NAME} ${OpenCV_LIBRARIES}) endif() ament_auto_package( diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/launch/ar_tag_based_localizer.launch.xml b/localization/landmark_based_localizer/ar_tag_based_localizer/launch/ar_tag_based_localizer.launch.xml index 272338905c3f0..34602ca70daf4 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/launch/ar_tag_based_localizer.launch.xml +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/launch/ar_tag_based_localizer.launch.xml @@ -14,7 +14,7 @@ - + diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml b/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml index 072479cc7aaf5..90fdd2fee31f4 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/package.xml @@ -24,6 +24,7 @@ lanelet2_extension localization_util rclcpp + rclcpp_components tf2_eigen tf2_geometry_msgs tf2_ros diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp index 43ac1e1098453..9a6823e330acd 100644 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp +++ b/localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp @@ -65,7 +65,7 @@ #include ArTagBasedLocalizer::ArTagBasedLocalizer(const rclcpp::NodeOptions & options) -: Node("ar_tag_based_localizer", options), cam_info_received_(false) +: rclcpp::Node("ar_tag_based_localizer", options), cam_info_received_(false) { /* Declare node parameters @@ -346,3 +346,6 @@ std::vector ArTagBasedLocalizer::detect_landmarks( return landmarks; } + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(ArTagBasedLocalizer) diff --git a/localization/landmark_based_localizer/ar_tag_based_localizer/src/main.cpp b/localization/landmark_based_localizer/ar_tag_based_localizer/src/main.cpp deleted file mode 100644 index 8ef1dd6195580..0000000000000 --- a/localization/landmark_based_localizer/ar_tag_based_localizer/src/main.cpp +++ /dev/null @@ -1,53 +0,0 @@ -// Copyright 2023 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. - -// This source code is derived from the https://github.com/pal-robotics/aruco_ros. -// Here is the license statement. -/***************************** - Copyright 2011 Rafael Muñoz Salinas. All rights reserved. - - Redistribution and use in source and binary forms, with or without modification, are - permitted provided that the following conditions are met: - - 1. Redistributions of source code must retain the above copyright notice, this list of - conditions and the following disclaimer. - - 2. Redistributions in binary form must reproduce the above copyright notice, this list - of conditions and the following disclaimer in the documentation and/or other materials - provided with the distribution. - - THIS SOFTWARE IS PROVIDED BY Rafael Muñoz Salinas ''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 Rafael Muñoz Salinas 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. - - The views and conclusions contained in the software and documentation are those of the - authors and should not be interpreted as representing official policies, either expressed - or implied, of Rafael Muñoz Salinas. - ********************************/ - -#include "ar_tag_based_localizer.hpp" - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - std::shared_ptr ptr = std::make_shared(); - rclcpp::spin(ptr); - rclcpp::shutdown(); -} diff --git a/localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp b/localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp index 57bfcde461af6..e977dbf6cf74a 100644 --- a/localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp +++ b/localization/landmark_based_localizer/landmark_manager/src/landmark_manager.cpp @@ -50,7 +50,7 @@ void LandmarkManager::parse_landmarks( const auto & v2 = vertices[2]; const auto & v3 = vertices[3]; const double volume = (v1 - v0).cross(v2 - v0).dot(v3 - v0) / 6.0; - const double volume_threshold = 1e-5; + const double volume_threshold = 1e-3; if (volume > volume_threshold) { continue; } diff --git a/localization/localization_error_monitor/CMakeLists.txt b/localization/localization_error_monitor/CMakeLists.txt index 3528367486350..c27e51e6e0359 100644 --- a/localization/localization_error_monitor/CMakeLists.txt +++ b/localization/localization_error_monitor/CMakeLists.txt @@ -4,15 +4,16 @@ project(localization_error_monitor) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_library(localization_error_monitor_module SHARED +ament_auto_add_library(${PROJECT_NAME} SHARED src/diagnostics.cpp + src/localization_error_monitor.cpp ) -ament_auto_add_executable(localization_error_monitor - src/main.cpp - src/node.cpp +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "LocalizationErrorMonitor" + EXECUTABLE ${PROJECT_NAME}_node + EXECUTOR SingleThreadedExecutor ) -target_link_libraries(localization_error_monitor localization_error_monitor_module) if(BUILD_TESTING) function(add_testcase filepath) @@ -20,17 +21,17 @@ if(BUILD_TESTING) string(REGEX REPLACE ".cpp" "" test_name ${filename}) ament_add_gtest(${test_name} ${filepath}) target_include_directories(${test_name} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}/include) - target_link_libraries(${test_name} localization_error_monitor_module) + target_link_libraries(${test_name} ${PROJECT_NAME}) ament_target_dependencies(${test_name} ${${PROJECT_NAME}_FOUND_BUILD_DEPENDS}) endfunction() - find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() add_testcase(test/test_diagnostics.cpp) endif() -ament_auto_package(INSTALL_TO_SHARE +ament_auto_package( + INSTALL_TO_SHARE config launch ) diff --git a/localization/localization_error_monitor/include/localization_error_monitor/node.hpp b/localization/localization_error_monitor/include/localization_error_monitor/localization_error_monitor.hpp similarity index 87% rename from localization/localization_error_monitor/include/localization_error_monitor/node.hpp rename to localization/localization_error_monitor/include/localization_error_monitor/localization_error_monitor.hpp index 296b278004333..6016677d88136 100644 --- a/localization/localization_error_monitor/include/localization_error_monitor/node.hpp +++ b/localization/localization_error_monitor/include/localization_error_monitor/localization_error_monitor.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef LOCALIZATION_ERROR_MONITOR__NODE_HPP_ -#define LOCALIZATION_ERROR_MONITOR__NODE_HPP_ +#ifndef LOCALIZATION_ERROR_MONITOR__LOCALIZATION_ERROR_MONITOR_HPP_ +#define LOCALIZATION_ERROR_MONITOR__LOCALIZATION_ERROR_MONITOR_HPP_ #include #include @@ -58,7 +58,7 @@ class LocalizationErrorMonitor : public rclcpp::Node double measureSizeEllipseAlongBodyFrame(const Eigen::Matrix2d & Pinv, double theta); public: - LocalizationErrorMonitor(); + explicit LocalizationErrorMonitor(const rclcpp::NodeOptions & options); ~LocalizationErrorMonitor() = default; }; -#endif // LOCALIZATION_ERROR_MONITOR__NODE_HPP_ +#endif // LOCALIZATION_ERROR_MONITOR__LOCALIZATION_ERROR_MONITOR_HPP_ diff --git a/localization/localization_error_monitor/launch/localization_error_monitor.launch.xml b/localization/localization_error_monitor/launch/localization_error_monitor.launch.xml index eb2b5741b00fc..ad3e8beff92ab 100644 --- a/localization/localization_error_monitor/launch/localization_error_monitor.launch.xml +++ b/localization/localization_error_monitor/launch/localization_error_monitor.launch.xml @@ -2,7 +2,7 @@ - + diff --git a/localization/localization_error_monitor/package.xml b/localization/localization_error_monitor/package.xml index a1b352d911a0d..0138451b069e4 100644 --- a/localization/localization_error_monitor/package.xml +++ b/localization/localization_error_monitor/package.xml @@ -23,6 +23,7 @@ diagnostic_msgs diagnostic_updater nav_msgs + rclcpp_components tf2 tf2_geometry_msgs tier4_autoware_utils diff --git a/localization/localization_error_monitor/src/node.cpp b/localization/localization_error_monitor/src/localization_error_monitor.cpp similarity index 93% rename from localization/localization_error_monitor/src/node.cpp rename to localization/localization_error_monitor/src/localization_error_monitor.cpp index f47372a0158b2..7a1cd0b213c39 100644 --- a/localization/localization_error_monitor/src/node.cpp +++ b/localization/localization_error_monitor/src/localization_error_monitor.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "localization_error_monitor/node.hpp" +#include "localization_error_monitor/localization_error_monitor.hpp" #include "localization_error_monitor/diagnostics.hpp" @@ -32,7 +32,8 @@ #include #include -LocalizationErrorMonitor::LocalizationErrorMonitor() : Node("localization_error_monitor") +LocalizationErrorMonitor::LocalizationErrorMonitor(const rclcpp::NodeOptions & options) +: Node("localization_error_monitor", options) { scale_ = this->declare_parameter("scale"); error_ellipse_size_ = this->declare_parameter("error_ellipse_size"); @@ -128,7 +129,7 @@ void LocalizationErrorMonitor::onOdom(nav_msgs::msg::Odometry::ConstSharedPtr in diag_merged_status.hardware_id = this->get_name(); diagnostic_msgs::msg::DiagnosticArray diag_msg; - diag_msg.header.stamp = this->now(); + diag_msg.header.stamp = input_msg->header.stamp; diag_msg.status.push_back(diag_merged_status); diag_pub_->publish(diag_msg); } @@ -143,3 +144,6 @@ double LocalizationErrorMonitor::measureSizeEllipseAlongBodyFrame( double d = std::sqrt((e.transpose() * Pinv * e)(0, 0) / Pinv.determinant()); return d; } + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(LocalizationErrorMonitor) diff --git a/localization/localization_error_monitor/src/main.cpp b/localization/localization_error_monitor/src/main.cpp deleted file mode 100644 index f4fa5ab664005..0000000000000 --- a/localization/localization_error_monitor/src/main.cpp +++ /dev/null @@ -1,28 +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 "localization_error_monitor/node.hpp" - -#include - -#include - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - auto node = std::make_shared(); - rclcpp::spin(node); - rclcpp::shutdown(); - return 0; -} diff --git a/localization/ndt_scan_matcher/CMakeLists.txt b/localization/ndt_scan_matcher/CMakeLists.txt index 4806838cf0103..5e4db9571c404 100644 --- a/localization/ndt_scan_matcher/CMakeLists.txt +++ b/localization/ndt_scan_matcher/CMakeLists.txt @@ -22,19 +22,24 @@ else() endif() endif() -find_package(glog REQUIRED) find_package(PCL REQUIRED COMPONENTS common io registration) include_directories(${PCL_INCLUDE_DIRS}) -ament_auto_add_executable(ndt_scan_matcher - src/particle.cpp - src/ndt_scan_matcher_node.cpp - src/ndt_scan_matcher_core.cpp +ament_auto_add_library(${PROJECT_NAME} SHARED + src/diagnostics_module.cpp src/map_update_module.cpp + src/ndt_scan_matcher_core.cpp + src/particle.cpp ) link_directories(${PCL_LIBRARY_DIRS}) -target_link_libraries(ndt_scan_matcher ${PCL_LIBRARIES} glog::glog) +target_link_libraries(ndt_scan_matcher ${PCL_LIBRARIES}) + +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "NDTScanMatcher" + EXECUTABLE ${PROJECT_NAME}_node + EXECUTOR MultiThreadedExecutor +) if(BUILD_TESTING) add_launch_test( @@ -45,15 +50,9 @@ if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) ament_auto_add_gtest(standard_sequence_for_initial_pose_estimation test/test_cases/standard_sequence_for_initial_pose_estimation.cpp - src/particle.cpp - src/ndt_scan_matcher_core.cpp - src/map_update_module.cpp ) ament_auto_add_gtest(once_initialize_at_out_of_map_then_initialize_correctly test/test_cases/once_initialize_at_out_of_map_then_initialize_correctly.cpp - src/particle.cpp - src/ndt_scan_matcher_core.cpp - src/map_update_module.cpp ) endif() diff --git a/localization/ndt_scan_matcher/README.md b/localization/ndt_scan_matcher/README.md index 424a7051de883..a44db7bbaa4bf 100644 --- a/localization/ndt_scan_matcher/README.md +++ b/localization/ndt_scan_matcher/README.md @@ -255,3 +255,103 @@ initial_pose_offset_model is rotated around (x,y) = (0,0) in the direction of th initial_pose_offset_model_x & initial_pose_offset_model_y must have the same number of elements. {{ json_to_markdown("localization/ndt_scan_matcher/schema/sub/covariance_covariance_estimation.json") }} + +## Diagnostics + +### scan_matching_status + +drawing + +| Name | Description | Transition condition to Warning | Transition condition to Error | Whether to reject the estimation result (affects `skipping_publish_num`) | +| ----------------------------------------- | -------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ----------------------------- | --------------------------------------------------------------------------------------------------- | +| `topic_time_stamp` | the time stamp of input topic | none | none | no | +| `sensor_points_size` | the size of sensor points | the size is 0 | none | yes | +| `sensor_points_delay_time_sec` | the delay time of sensor points | the time is **longer** than `validation.lidar_topic_timeout_sec` | none | yes | +| `is_succeed_transform_sensor_points` | whether transform sensor points is succeed or not | none | failed | yes | +| `sensor_points_max_distance` | the max distance of sensor points | the max distance is **shorter** than `sensor_points.required_distance` | none | yes | +| `is_activated` | whether the node is in the "activate" state or not | not "activate" state | none | if `is_activated` is false, then estimation is not executed and `skipping_publish_num` is set to 0. | +| `is_succeed_interpolate_initial_pose` | whether the interpolate of initial pose is succeed or not | failed.
(1) the size of `initial_pose_buffer_` is **smaller** than 2.
(2) the timestamp difference between initial_pose and sensor pointcloud is **longer** than `validation.initial_pose_timeout_sec`.
(3) distance difference between two initial poses used for linear interpolation is **longer** than `validation.initial_pose_distance_tolerance_m` | none | yes | +| `is_set_map_points` | whether the map points is set or not | not set | none | yes | +| `iteration_num` | the number of times calculate alignment | the number of times is **larger** than `ndt.max_iterations` | none | yes | +| `local_optimal_solution_oscillation_num` | the number of times the solution is judged to be oscillating | the number of times is **larger** than 10 | none | yes | +| `transform_probability` | the score of how well the map aligns with the sensor points | the score is **smaller** than`score_estimation.converged_param_transform_probability` (only in the case of `score_estimation.converged_param_type` is 0=TRANSFORM_PROBABILITY) | none | yes | +| `nearest_voxel_transformation_likelihood` | the score of how well the map aligns with the sensor points | the score is **smaller** than `score_estimation.converged_param_nearest_voxel_transformation_likelihood` (only in the case of `score_estimation.converged_param_type` is 1=NEAREST_VOXEL_TRANSFORMATION_LIKELIHOOD) | none | yes | +| `distance_initial_to_result` | the distance between the position before convergence processing and the position after | the distance is **longer** than 3 | none | no | +| `execution_time` | the time for convergence processing | the time is **longer** than `validation.critical_upper_bound_exe_time_ms` | none | no | +| `skipping_publish_num` | the number of times rejected estimation results consecutively | the number of times is 5 or more | none | - | + +※The `sensor_points_callback` shares the same callback group as the `trigger_node_service` and `ndt_align_service`. Consequently, if the initial pose estimation takes too long, this diagnostic may become stale. + +### initial_pose_subscriber_status + +drawing + +| Name | Description | Transition condition to Warning | Transition condition to Error | +| ---------------------- | ------------------------------------------------------------------ | ------------------------------- | ----------------------------- | +| `topic_time_stamp` | the time stamp of input topic | none | none | +| `is_activated` | whether the node is in the "activate" state or not | not "activate" state | none | +| `is_expected_frame_id` | whether the input frame_id is the same as `frame.map_frame` or not | none | not the same | + +### regularization_pose_subscriber_status + +drawing + +| Name | Description | Transition condition to Warning | Transition condition to Error | +| ------------------ | ----------------------------- | ------------------------------- | ----------------------------- | +| `topic_time_stamp` | the time stamp of input topic | none | none | + +### trigger_node_service_status + +drawing + +| Name | Description | Transition condition to Warning | Transition condition to Error | +| ------------------------- | -------------------------------------------------- | ------------------------------- | ----------------------------- | +| `service_call_time_stamp` | the time stamp of service calling | none | none | +| `is_activated` | whether the node is in the "activate" state or not | none | none | +| `is_succeed_service` | whether the process of service is succeed or not | none | none | + +※ +This diagnostic is only published when the service is called, so it becomes stale after the initial pose estimation is completed. + +### ndt_align_service_status + +drawing + +| Name | Description | Transition condition to Warning | Transition condition to Error | +| ----------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------- | ----------------------------------------------------------- | +| `service_call_time_stamp` | the time stamp of service calling | none | none | +| `is_succeed_transform_initial_pose` | whether transform initial pose is succeed or not | none | failed | +| `is_need_rebuild` | whether it need to rebuild the map. If the map has not been loaded yet or if `distance_last_update_position_to_current_position encounters` is an Error state, it is considered necessary to reconstruct the map, and `is_need_rebuild` becomes `True`. | none | none | +| `maps_size_before` | the number of maps before update map | none | none | +| `is_succeed_call_pcd_loader` | whether call pcd_loader service is succeed or not | failed | none | +| `maps_to_add_size` | the number of maps to be added | none | none | +| `maps_to_remove_size` | the number of maps to be removed | none | none | +| `map_update_execution_time` | the time for map updating | none | none | +| `maps_size_after` | the number of maps after update map | none | none | +| `is_updated_map` | whether map is updated. If the map update couldn't be performed or there was no need to update the map, it becomes `False` | none | `is_updated_map` is `False` but `is_need_rebuild` is `True` | +| `is_set_map_points` | whether the map points is set or not | not set | none | +| `is_set_sensor_points` | whether the sensor points is set or not | not set | none | +| `best_particle_score` | the best score of particle | none | none | +| `is_succeed_service` | whether the process of service is succeed or not | failed | none | + +※ +This diagnostic is only published when the service is called, so it becomes stale after the initial pose estimation is completed. + +### map_update_status + +drawing + +| Name | Description | Transition condition to Warning | Transition condition to Error | +| --------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------- | ------------------------------------------------------------------------------------------------------- | +| `timer_callback_time_stamp` | the time stamp of timer_callback calling | none | none | +| `is_activated` | whether the node is in the "activate" state or not | not "activate" state | none | +| `is_set_last_update_position` | whether the `last_update_position` is set or not | not set | none | +| `distance_last_update_position_to_current_position` | the distance of `last_update_position` to current position | none | (the distance + `dynamic_map_loading.lidar_radius`) is **larger** than `dynamic_map_loading.map_radius` | +| `is_need_rebuild` | whether it need to rebuild the map. If the map has not been loaded yet or if `distance_last_update_position_to_current_position encounters` is an Error state, it is considered necessary to reconstruct the map, and `is_need_rebuild` becomes `True`. | none | none | +| `maps_size_before` | the number of maps before update map | none | none | +| `is_succeed_call_pcd_loader` | whether call pcd_loader service is succeed or not | failed | none | +| `maps_to_add_size` | the number of maps to be added | none | none | +| `maps_to_remove_size` | the number of maps to be removed | none | none | +| `map_update_execution_time` | the time for map updating | none | none | +| `maps_size_after` | the number of maps after update map | none | none | +| `is_updated_map` | whether map is updated. If the map update couldn't be performed or there was no need to update the map, it becomes `False` | none | `is_updated_map` is `False` but `is_need_rebuild` is `True` | 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/include/ndt_scan_matcher/diagnostics_module.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/diagnostics_module.hpp new file mode 100644 index 0000000000000..4f7b5eff6521b --- /dev/null +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/diagnostics_module.hpp @@ -0,0 +1,60 @@ +// Copyright 2023 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 NDT_SCAN_MATCHER__DIAGNOSTICS_MODULE_HPP_ +#define NDT_SCAN_MATCHER__DIAGNOSTICS_MODULE_HPP_ + +#include + +#include + +#include +#include + +class DiagnosticsModule +{ +public: + DiagnosticsModule(rclcpp::Node * node, const std::string & diagnostic_name); + void clear(); + void addKeyValue(const diagnostic_msgs::msg::KeyValue & key_value_msg); + template + void addKeyValue(const std::string & key, const T & value); + void updateLevelAndMessage(const int8_t level, const std::string & message); + void publish(const rclcpp::Time & publish_time_stamp); + +private: + diagnostic_msgs::msg::DiagnosticArray createDiagnosticsArray( + const rclcpp::Time & publish_time_stamp) const; + + rclcpp::Clock::SharedPtr clock_; + rclcpp::Publisher::SharedPtr diagnostics_pub_; + + diagnostic_msgs::msg::DiagnosticStatus diagnostics_status_msg_; +}; + +template +void DiagnosticsModule::addKeyValue(const std::string & key, const T & value) +{ + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = key; + key_value.value = std::to_string(value); + addKeyValue(key_value); +} + +template <> +void DiagnosticsModule::addKeyValue(const std::string & key, const std::string & value); +template <> +void DiagnosticsModule::addKeyValue(const std::string & key, const bool & value); + +#endif // NDT_SCAN_MATCHER__DIAGNOSTICS_MODULE_HPP_ diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/hyper_parameters.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/hyper_parameters.hpp index ee1e2369c79bd..bc7bf1fe40d36 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/hyper_parameters.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/hyper_parameters.hpp @@ -20,6 +20,7 @@ #include #include +#include #include #include @@ -162,10 +163,11 @@ struct HyperParameters initial_pose_offset_model_y[i]; } } else { - RCLCPP_WARN( - node->get_logger(), - "Invalid initial pose offset model parameters. Disable covariance estimation."); - covariance.covariance_estimation.enable = false; + std::stringstream message; + message << "Invalid initial pose offset model parameters." + << "Please make sure that the number of elements in " + << "initial_pose_offset_model_x and initial_pose_offset_model_y are the same."; + throw std::runtime_error(message.str()); } } diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp index 04c762ae950a4..2bcb6f4cf6fb8 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/map_update_module.hpp @@ -16,6 +16,7 @@ #define NDT_SCAN_MATCHER__MAP_UPDATE_MODULE_HPP_ #include "localization_util/util_func.hpp" +#include "ndt_scan_matcher/diagnostics_module.hpp" #include "ndt_scan_matcher/hyper_parameters.hpp" #include "ndt_scan_matcher/particle.hpp" @@ -54,10 +55,20 @@ class MapUpdateModule private: friend class NDTScanMatcher; + void callback_timer( + const bool is_activated, const std::optional & position, + std::unique_ptr & diagnostics_ptr); + + [[nodiscard]] bool should_update_map( + const geometry_msgs::msg::Point & position, + std::unique_ptr & diagnostics_ptr); + void update_map( + const geometry_msgs::msg::Point & position, + std::unique_ptr & diagnostics_ptr); // Update the specified NDT - bool update_ndt(const geometry_msgs::msg::Point & position, NdtType & ndt); - void update_map(const geometry_msgs::msg::Point & position); - [[nodiscard]] bool should_update_map(const geometry_msgs::msg::Point & position); + bool update_ndt( + const geometry_msgs::msg::Point & position, NdtType & ndt, + std::unique_ptr & diagnostics_ptr); void publish_partial_pcd_map(); rclcpp::Publisher::SharedPtr loaded_pcd_pub_; diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp index 26c96ce7e3248..4f8042d106c75 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp @@ -18,6 +18,7 @@ #define FMT_HEADER_ONLY #include "localization_util/smart_pose_buffer.hpp" +#include "ndt_scan_matcher/diagnostics_module.hpp" #include "ndt_scan_matcher/hyper_parameters.hpp" #include "ndt_scan_matcher/map_update_module.hpp" @@ -62,6 +63,7 @@ #include #include #include +#include #include #include #include @@ -77,21 +79,32 @@ class NDTScanMatcher : public rclcpp::Node explicit NDTScanMatcher(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); private: - void service_ndt_align( - const tier4_localization_msgs::srv::PoseWithCovarianceStamped::Request::SharedPtr req, - tier4_localization_msgs::srv::PoseWithCovarianceStamped::Response::SharedPtr res); - void service_trigger_node( - const std_srvs::srv::SetBool::Request::SharedPtr req, - std_srvs::srv::SetBool::Response::SharedPtr res); - void callback_timer(); - void callback_sensor_points( - sensor_msgs::msg::PointCloud2::ConstSharedPtr sensor_points_msg_in_sensor_frame); + void callback_initial_pose( geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr initial_pose_msg_ptr); + void callback_initial_pose_main( + const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr initial_pose_msg_ptr); + void callback_regularization_pose( geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr pose_conv_msg_ptr); + void callback_sensor_points( + sensor_msgs::msg::PointCloud2::ConstSharedPtr sensor_points_msg_in_sensor_frame); + bool callback_sensor_points_main( + sensor_msgs::msg::PointCloud2::ConstSharedPtr sensor_points_msg_in_sensor_frame); + + void service_trigger_node( + const std_srvs::srv::SetBool::Request::SharedPtr req, + std_srvs::srv::SetBool::Response::SharedPtr res); + + void service_ndt_align( + const tier4_localization_msgs::srv::PoseWithCovarianceStamped::Request::SharedPtr req, + tier4_localization_msgs::srv::PoseWithCovarianceStamped::Response::SharedPtr res); + void service_ndt_align_main( + const tier4_localization_msgs::srv::PoseWithCovarianceStamped::Request::SharedPtr req, + tier4_localization_msgs::srv::PoseWithCovarianceStamped::Response::SharedPtr res); + geometry_msgs::msg::PoseWithCovarianceStamped align_pose( const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_with_cov); @@ -116,11 +129,6 @@ class NDTScanMatcher : public rclcpp::Node const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_old_msg, const geometry_msgs::msg::PoseWithCovarianceStamped & initial_pose_new_msg); - bool validate_num_iteration(const int iter_num, const int max_iter_num); - bool validate_score( - const double score, const double score_threshold, const std::string & score_name); - bool validate_converged_param( - const double & transform_probability, const double & nearest_voxel_transformation_likelihood); static int count_oscillation(const std::vector & result_pose_msg_array); std::array rotate_covariance( @@ -131,8 +139,6 @@ class NDTScanMatcher : public rclcpp::Node void add_regularization_pose(const rclcpp::Time & sensor_ros_time); - void publish_diagnostic(); - rclcpp::TimerBase::SharedPtr map_update_timer_; rclcpp::Subscription::SharedPtr initial_pose_sub_; rclcpp::Subscription::SharedPtr sensor_points_sub_; @@ -168,7 +174,6 @@ class NDTScanMatcher : public rclcpp::Node rclcpp::Publisher::SharedPtr ndt_marker_pub_; rclcpp::Publisher::SharedPtr ndt_monte_carlo_initial_pose_marker_pub_; - rclcpp::Publisher::SharedPtr diagnostics_pub_; rclcpp::Service::SharedPtr service_; rclcpp::Service::SharedPtr service_trigger_node_; @@ -180,7 +185,6 @@ class NDTScanMatcher : public rclcpp::Node rclcpp::CallbackGroup::SharedPtr timer_callback_group_; std::shared_ptr ndt_ptr_; - std::shared_ptr> state_ptr_; Eigen::Matrix4f base_to_sensor_matrix_; @@ -194,6 +198,12 @@ class NDTScanMatcher : public rclcpp::Node std::unique_ptr regularization_pose_buffer_; std::atomic is_activated_; + std::unique_ptr diagnostics_scan_points_; + std::unique_ptr diagnostics_initial_pose_; + std::unique_ptr diagnostics_regularization_pose_; + std::unique_ptr diagnostics_map_update_; + std::unique_ptr diagnostics_ndt_align_; + std::unique_ptr diagnostics_trigger_node_; std::unique_ptr map_update_module_; std::unique_ptr logger_configure_; diff --git a/localization/ndt_scan_matcher/launch/ndt_scan_matcher.launch.xml b/localization/ndt_scan_matcher/launch/ndt_scan_matcher.launch.xml index cbcb0a9f74bc4..671e2ace56cad 100644 --- a/localization/ndt_scan_matcher/launch/ndt_scan_matcher.launch.xml +++ b/localization/ndt_scan_matcher/launch/ndt_scan_matcher.launch.xml @@ -14,7 +14,7 @@ - + diff --git a/localization/ndt_scan_matcher/media/diagnostic_initial_pose_subscriber_status.png b/localization/ndt_scan_matcher/media/diagnostic_initial_pose_subscriber_status.png new file mode 100644 index 0000000000000..766888359ed8e Binary files /dev/null and b/localization/ndt_scan_matcher/media/diagnostic_initial_pose_subscriber_status.png differ diff --git a/localization/ndt_scan_matcher/media/diagnostic_map_update_status.png b/localization/ndt_scan_matcher/media/diagnostic_map_update_status.png new file mode 100644 index 0000000000000..0fe7016fe7e3c Binary files /dev/null and b/localization/ndt_scan_matcher/media/diagnostic_map_update_status.png differ diff --git a/localization/ndt_scan_matcher/media/diagnostic_ndt_align_service_status.png b/localization/ndt_scan_matcher/media/diagnostic_ndt_align_service_status.png new file mode 100644 index 0000000000000..e1da17966080f Binary files /dev/null and b/localization/ndt_scan_matcher/media/diagnostic_ndt_align_service_status.png differ diff --git a/localization/ndt_scan_matcher/media/diagnostic_regularization_pose_subscriber_status.png b/localization/ndt_scan_matcher/media/diagnostic_regularization_pose_subscriber_status.png new file mode 100644 index 0000000000000..6d777ff360481 Binary files /dev/null and b/localization/ndt_scan_matcher/media/diagnostic_regularization_pose_subscriber_status.png differ diff --git a/localization/ndt_scan_matcher/media/diagnostic_scan_matching_status.png b/localization/ndt_scan_matcher/media/diagnostic_scan_matching_status.png new file mode 100644 index 0000000000000..2687db23d4714 Binary files /dev/null and b/localization/ndt_scan_matcher/media/diagnostic_scan_matching_status.png differ diff --git a/localization/ndt_scan_matcher/media/diagnostic_trigger_node_service_status.png b/localization/ndt_scan_matcher/media/diagnostic_trigger_node_service_status.png new file mode 100644 index 0000000000000..178e2a8bf361f Binary files /dev/null and b/localization/ndt_scan_matcher/media/diagnostic_trigger_node_service_status.png differ diff --git a/localization/ndt_scan_matcher/package.xml b/localization/ndt_scan_matcher/package.xml index 0913ee04174f5..b62e810926331 100644 --- a/localization/ndt_scan_matcher/package.xml +++ b/localization/ndt_scan_matcher/package.xml @@ -22,13 +22,13 @@ diagnostic_msgs fmt geometry_msgs - libgoogle-glog-dev libpcl-all-dev localization_util nav_msgs ndt_omp pcl_conversions rclcpp + rclcpp_components sensor_msgs std_msgs std_srvs 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/diagnostics_module.cpp b/localization/ndt_scan_matcher/src/diagnostics_module.cpp new file mode 100644 index 0000000000000..1e08ebb89f51e --- /dev/null +++ b/localization/ndt_scan_matcher/src/diagnostics_module.cpp @@ -0,0 +1,105 @@ +// Copyright 2023 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 "ndt_scan_matcher/diagnostics_module.hpp" + +#include + +#include + +#include +#include + +DiagnosticsModule::DiagnosticsModule(rclcpp::Node * node, const std::string & diagnostic_name) +: clock_(node->get_clock()) +{ + diagnostics_pub_ = + node->create_publisher("/diagnostics", 10); + + diagnostics_status_msg_.name = + std::string(node->get_name()) + std::string(": ") + diagnostic_name; + diagnostics_status_msg_.hardware_id = node->get_name(); +} + +void DiagnosticsModule::clear() +{ + diagnostics_status_msg_.values.clear(); + diagnostics_status_msg_.values.shrink_to_fit(); + + diagnostics_status_msg_.level = diagnostic_msgs::msg::DiagnosticStatus::OK; + diagnostics_status_msg_.message = ""; +} + +void DiagnosticsModule::addKeyValue(const diagnostic_msgs::msg::KeyValue & key_value_msg) +{ + auto it = std::find_if( + std::begin(diagnostics_status_msg_.values), std::end(diagnostics_status_msg_.values), + [key_value_msg](const auto & arg) { return arg.key == key_value_msg.key; }); + + if (it != std::cend(diagnostics_status_msg_.values)) { + it->value = key_value_msg.value; + } else { + diagnostics_status_msg_.values.push_back(key_value_msg); + } +} + +template <> +void DiagnosticsModule::addKeyValue(const std::string & key, const std::string & value) +{ + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = key; + key_value.value = value; + addKeyValue(key_value); +} + +template <> +void DiagnosticsModule::addKeyValue(const std::string & key, const bool & value) +{ + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = key; + key_value.value = value ? "True" : "False"; + addKeyValue(key_value); +} + +void DiagnosticsModule::updateLevelAndMessage(const int8_t level, const std::string & message) +{ + if ((level > diagnostic_msgs::msg::DiagnosticStatus::OK)) { + if (!diagnostics_status_msg_.message.empty()) { + diagnostics_status_msg_.message += "; "; + } + diagnostics_status_msg_.message += message; + } + if (level > diagnostics_status_msg_.level) { + diagnostics_status_msg_.level = level; + } +} + +void DiagnosticsModule::publish(const rclcpp::Time & publish_time_stamp) +{ + diagnostics_pub_->publish(createDiagnosticsArray(publish_time_stamp)); +} + +diagnostic_msgs::msg::DiagnosticArray DiagnosticsModule::createDiagnosticsArray( + const rclcpp::Time & publish_time_stamp) const +{ + diagnostic_msgs::msg::DiagnosticArray diagnostics_msg; + diagnostics_msg.header.stamp = publish_time_stamp; + diagnostics_msg.status.push_back(diagnostics_status_msg_); + + if (diagnostics_msg.status.at(0).level == diagnostic_msgs::msg::DiagnosticStatus::OK) { + diagnostics_msg.status.at(0).message = "OK"; + } + + return diagnostics_msg; +} diff --git a/localization/ndt_scan_matcher/src/map_update_module.cpp b/localization/ndt_scan_matcher/src/map_update_module.cpp index ca56a93cec859..40f0b1f4465fa 100644 --- a/localization/ndt_scan_matcher/src/map_update_module.cpp +++ b/localization/ndt_scan_matcher/src/map_update_module.cpp @@ -34,7 +34,10 @@ MapUpdateModule::MapUpdateModule( if (ndt_ptr_) { *secondary_ndt_ptr_ = *ndt_ptr_; } else { - RCLCPP_ERROR_STREAM_THROTTLE(logger_, *clock_, 1000, "Attempt to update a null NDT pointer."); + std::stringstream message; + message << "Error at MapUpdateModule::MapUpdateModule." + << "`ndt_ptr_` is a null NDT pointer."; + throw std::runtime_error(message.str()); } // Initially, a direct map update on ndt_ptr_ is needed. @@ -45,7 +48,39 @@ MapUpdateModule::MapUpdateModule( need_rebuild_ = true; } -bool MapUpdateModule::should_update_map(const geometry_msgs::msg::Point & position) +void MapUpdateModule::callback_timer( + const bool is_activated, const std::optional & position, + std::unique_ptr & diagnostics_ptr) +{ + // check is_activated + diagnostics_ptr->addKeyValue("is_activated", is_activated); + if (!is_activated) { + std::stringstream message; + message << "Node is not activated."; + diagnostics_ptr->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + return; + } + + // check is_set_last_update_position + const bool is_set_last_update_position = (position != std::nullopt); + diagnostics_ptr->addKeyValue("is_set_last_update_position", is_set_last_update_position); + if (!is_set_last_update_position) { + std::stringstream message; + message << "Cannot find the reference position for map update." + << "Please check if the EKF odometry is provided to NDT."; + diagnostics_ptr->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + return; + } + + if (should_update_map(position.value(), diagnostics_ptr)) { + update_map(position.value(), diagnostics_ptr); + } +} + +bool MapUpdateModule::should_update_map( + const geometry_msgs::msg::Point & position, std::unique_ptr & diagnostics_ptr) { if (last_update_position_ == std::nullopt) { need_rebuild_ = true; @@ -55,8 +90,15 @@ bool MapUpdateModule::should_update_map(const geometry_msgs::msg::Point & positi const double dx = position.x - last_update_position_.value().x; const double dy = position.y - last_update_position_.value().y; const double distance = std::hypot(dx, dy); + + // check distance_last_update_position_to_current_position + diagnostics_ptr->addKeyValue("distance_last_update_position_to_current_position", distance); if (distance + param_.lidar_radius > param_.map_radius) { - RCLCPP_ERROR_STREAM_THROTTLE(logger_, *clock_, 1000, "Dynamic map loading is not keeping up."); + std::stringstream message; + message << "Dynamic map loading is not keeping up."; + diagnostics_ptr->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); + // If the map does not keep up with the current position, // lock ndt_ptr_ entirely until it is fully rebuilt. need_rebuild_ = true; @@ -65,8 +107,11 @@ bool MapUpdateModule::should_update_map(const geometry_msgs::msg::Point & positi return distance > param_.update_distance; } -void MapUpdateModule::update_map(const geometry_msgs::msg::Point & position) +void MapUpdateModule::update_map( + const geometry_msgs::msg::Point & position, std::unique_ptr & diagnostics_ptr) { + diagnostics_ptr->addKeyValue("is_need_rebuild", need_rebuild_); + // If the current position is super far from the previous loading position, // lock and rebuild ndt_ptr_ if (need_rebuild_) { @@ -82,25 +127,37 @@ void MapUpdateModule::update_map(const geometry_msgs::msg::Point & position) ndt_ptr_->setInputSource(input_source); } - const bool updated = update_ndt(position, *ndt_ptr_); + const bool updated = update_ndt(position, *ndt_ptr_, diagnostics_ptr); + + // check is_updated_map + diagnostics_ptr->addKeyValue("is_updated_map", updated); if (!updated) { - RCLCPP_ERROR_STREAM_THROTTLE( - logger_, *clock_, 1000, - "update_ndt failed. If this happens with initial position estimation, make sure that" - "(1) the initial position matches the pcd map and (2) the map_loader is working properly."); + std::stringstream message; + message + << "update_ndt failed. If this happens with initial position estimation, make sure that" + << "(1) the initial position matches the pcd map and (2) the map_loader is working " + "properly."; + diagnostics_ptr->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); + RCLCPP_ERROR_STREAM_THROTTLE(logger_, *clock_, 1000, message.str()); last_update_position_ = position; ndt_ptr_mutex_->unlock(); return; } + ndt_ptr_mutex_->unlock(); need_rebuild_ = false; + } else { // Load map to the secondary_ndt_ptr, which does not require a mutex lock // Since the update of the secondary ndt ptr and the NDT align (done on // the main ndt_ptr_) overlap, the latency of updating/alignment reduces partly. // If the updating is done the main ndt_ptr_, either the update or the NDT // align will be blocked by the other. - const bool updated = update_ndt(position, *secondary_ndt_ptr_); + const bool updated = update_ndt(position, *secondary_ndt_ptr_, diagnostics_ptr); + + // check is_updated_map + diagnostics_ptr->addKeyValue("is_updated_map", updated); if (!updated) { last_update_position_ = position; return; @@ -128,8 +185,12 @@ void MapUpdateModule::update_map(const geometry_msgs::msg::Point & position) publish_partial_pcd_map(); } -bool MapUpdateModule::update_ndt(const geometry_msgs::msg::Point & position, NdtType & ndt) +bool MapUpdateModule::update_ndt( + const geometry_msgs::msg::Point & position, NdtType & ndt, + std::unique_ptr & diagnostics_ptr) { + diagnostics_ptr->addKeyValue("maps_size_before", ndt.getCurrentMapIDs().size()); + auto request = std::make_shared(); request->area.center_x = static_cast(position.x); @@ -138,7 +199,13 @@ bool MapUpdateModule::update_ndt(const geometry_msgs::msg::Point & position, Ndt request->cached_ids = ndt.getCurrentMapIDs(); while (!pcd_loader_client_->wait_for_service(std::chrono::seconds(1)) && rclcpp::ok()) { - RCLCPP_INFO(logger_, "Waiting for pcd loader service. Check the pointcloud_map_loader."); + diagnostics_ptr->addKeyValue("is_succeed_call_pcd_loader", false); + + std::stringstream message; + message << "Waiting for pcd loader service. Check the pointcloud_map_loader."; + diagnostics_ptr->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + return false; } // send a request to map_loader @@ -148,20 +215,27 @@ bool MapUpdateModule::update_ndt(const geometry_msgs::msg::Point & position, Ndt std::future_status status = result.wait_for(std::chrono::seconds(0)); while (status != std::future_status::ready) { - RCLCPP_INFO(logger_, "waiting response"); + // check is_succeed_call_pcd_loader if (!rclcpp::ok()) { + diagnostics_ptr->addKeyValue("is_succeed_call_pcd_loader", false); + + std::stringstream message; + message << "pcd_loader service is not working."; + diagnostics_ptr->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); return false; // No update } status = result.wait_for(std::chrono::seconds(1)); } + diagnostics_ptr->addKeyValue("is_succeed_call_pcd_loader", true); auto & maps_to_add = result.get()->new_pointcloud_with_ids; auto & map_ids_to_remove = result.get()->ids_to_remove; - RCLCPP_INFO( - logger_, "Update map (Add: %lu, Remove: %lu)", maps_to_add.size(), map_ids_to_remove.size()); + diagnostics_ptr->addKeyValue("maps_to_add_size", maps_to_add.size()); + diagnostics_ptr->addKeyValue("maps_to_remove_size", map_ids_to_remove.size()); + if (maps_to_add.empty() && map_ids_to_remove.empty()) { - RCLCPP_INFO(logger_, "Skip map update"); return false; // No update } @@ -187,7 +261,9 @@ bool MapUpdateModule::update_ndt(const geometry_msgs::msg::Point & position, Ndt const auto duration_micro_sec = std::chrono::duration_cast(exe_end_time - exe_start_time).count(); const auto exe_time = static_cast(duration_micro_sec) / 1000.0; - RCLCPP_DEBUG(logger_, "Time duration for creating new ndt_ptr: %lf [ms]", exe_time); + diagnostics_ptr->addKeyValue("map_update_execution_time", exe_time); + diagnostics_ptr->addKeyValue("maps_size_after", ndt.getCurrentMapIDs().size()); + diagnostics_ptr->addKeyValue("is_succeed_call_pcd_loader", true); return true; // Updated } 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 ba4190d9f66fb..8acfe3bd5c1ca 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 @@ -70,12 +68,9 @@ NDTScanMatcher::NDTScanMatcher(const rclcpp::NodeOptions & options) tf2_buffer_(this->get_clock()), tf2_listener_(tf2_buffer_), ndt_ptr_(new NormalDistributionsTransform), - state_ptr_(new std::map), is_activated_(false), param_(this) { - (*state_ptr_)["state"] = "Initializing"; - timer_callback_group_ = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); rclcpp::CallbackGroup::SharedPtr initial_pose_callback_group = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); @@ -117,6 +112,9 @@ NDTScanMatcher::NDTScanMatcher(const rclcpp::NodeOptions & options) const double value_as_unlimited = 1000.0; regularization_pose_buffer_ = std::make_unique(this->get_logger(), value_as_unlimited, value_as_unlimited); + + diagnostics_regularization_pose_ = + std::make_unique(this, "regularization_pose_subscriber_status"); } sensor_aligned_pose_pub_ = @@ -158,8 +156,6 @@ NDTScanMatcher::NDTScanMatcher(const rclcpp::NodeOptions & options) this->create_publisher( "initial_to_result_distance_new", 10); ndt_marker_pub_ = this->create_publisher("ndt_marker", 10); - diagnostics_pub_ = - this->create_publisher("/diagnostics", 10); ndt_monte_carlo_initial_pose_marker_pub_ = this->create_publisher( "monte_carlo_initial_pose_marker", 10); @@ -184,112 +180,73 @@ NDTScanMatcher::NDTScanMatcher(const rclcpp::NodeOptions & options) map_update_module_ = std::make_unique(this, &ndt_ptr_mtx_, ndt_ptr_, param_.dynamic_map_loading); + diagnostics_scan_points_ = std::make_unique(this, "scan_matching_status"); + diagnostics_initial_pose_ = + std::make_unique(this, "initial_pose_subscriber_status"); + diagnostics_map_update_ = std::make_unique(this, "map_update_status"); + diagnostics_ndt_align_ = std::make_unique(this, "ndt_align_service_status"); + diagnostics_trigger_node_ = + std::make_unique(this, "trigger_node_service_status"); + logger_configure_ = std::make_unique(this); } -void NDTScanMatcher::publish_diagnostic() +void NDTScanMatcher::callback_timer() { - diagnostic_msgs::msg::DiagnosticStatus diag_status_msg; - diag_status_msg.name = "ndt_scan_matcher"; - diag_status_msg.hardware_id = ""; - - for (const auto & key_value : (*state_ptr_)) { - diagnostic_msgs::msg::KeyValue key_value_msg; - key_value_msg.key = key_value.first; - key_value_msg.value = key_value.second; - diag_status_msg.values.push_back(key_value_msg); - } - - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::OK; - diag_status_msg.message = ""; - if (state_ptr_->count("state") && (*state_ptr_)["state"] == "Initializing") { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - diag_status_msg.message += "Initializing State. "; - } - if ( - state_ptr_->count("lidar_topic_delay_time_sec") && - std::stod((*state_ptr_)["lidar_topic_delay_time_sec"]) > - param_.validation.lidar_topic_timeout_sec) { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - diag_status_msg.message += "lidar_topic_delay_time_sec exceed limit. "; - } - if ( - state_ptr_->count("skipping_publish_num") && - std::stoi((*state_ptr_)["skipping_publish_num"]) > 1 && - std::stoi((*state_ptr_)["skipping_publish_num"]) < 5) { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - diag_status_msg.message += "skipping_publish_num > 1. "; - } - if ( - state_ptr_->count("skipping_publish_num") && - std::stoi((*state_ptr_)["skipping_publish_num"]) >= 5) { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - diag_status_msg.message += "skipping_publish_num exceed limit. "; - } - if ( - state_ptr_->count("nearest_voxel_transformation_likelihood") && - std::stod((*state_ptr_)["nearest_voxel_transformation_likelihood"]) < - param_.score_estimation.converged_param_nearest_voxel_transformation_likelihood) { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - diag_status_msg.message += "NDT score is unreliably low. "; - } - if ( - state_ptr_->count("execution_time") && std::stod((*state_ptr_)["execution_time"]) >= - param_.validation.critical_upper_bound_exe_time_ms) { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - diag_status_msg.message += - "NDT exe time is too long. (took " + (*state_ptr_)["execution_time"] + " [ms])"; - } - // Ignore local optimal solution - if ( - state_ptr_->count("is_local_optimal_solution_oscillation") && - std::stoi((*state_ptr_)["is_local_optimal_solution_oscillation"])) { - diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::OK; - diag_status_msg.message = "local optimal solution oscillation occurred"; - } - - diagnostic_msgs::msg::DiagnosticArray diag_msg; - diag_msg.header.stamp = this->now(); - diag_msg.status.push_back(diag_status_msg); - - diagnostics_pub_->publish(diag_msg); + const rclcpp::Time ros_time_now = this->now(); + + diagnostics_map_update_->clear(); + + diagnostics_map_update_->addKeyValue("timer_callback_time_stamp", ros_time_now.nanoseconds()); + + map_update_module_->callback_timer(is_activated_, latest_ekf_position_, diagnostics_map_update_); + + diagnostics_map_update_->publish(ros_time_now); } -void NDTScanMatcher::callback_timer() +void NDTScanMatcher::callback_initial_pose( + const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr initial_pose_msg_ptr) { - if (!is_activated_) { - return; - } - std::lock_guard lock(latest_ekf_position_mtx_); - if (latest_ekf_position_ == std::nullopt) { - RCLCPP_ERROR_STREAM_THROTTLE( - this->get_logger(), *this->get_clock(), 1000, - "Cannot find the reference position for map update. Please check if the EKF odometry is " - "provided to NDT."); - return; - } - // continue only if we should update the map - if (map_update_module_->should_update_map(latest_ekf_position_.value())) { - RCLCPP_INFO(this->get_logger(), "Start updating NDT map (timer_callback)"); - map_update_module_->update_map(latest_ekf_position_.value()); - } + diagnostics_initial_pose_->clear(); + + callback_initial_pose_main(initial_pose_msg_ptr); + + diagnostics_initial_pose_->publish(initial_pose_msg_ptr->header.stamp); } -void NDTScanMatcher::callback_initial_pose( +void NDTScanMatcher::callback_initial_pose_main( const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr initial_pose_msg_ptr) { - if (!is_activated_) return; + diagnostics_initial_pose_->addKeyValue( + "topic_time_stamp", + static_cast(initial_pose_msg_ptr->header.stamp).nanoseconds()); - if (initial_pose_msg_ptr->header.frame_id == param_.frame.map_frame) { - initial_pose_buffer_->push_back(initial_pose_msg_ptr); - } else { - RCLCPP_ERROR_STREAM_THROTTLE( - get_logger(), *this->get_clock(), 1000, - "Received initial pose message with frame_id " - << initial_pose_msg_ptr->header.frame_id << ", but expected " << param_.frame.map_frame - << ". Please check the frame_id in the input topic and ensure it is correct."); + // check is_activated + diagnostics_initial_pose_->addKeyValue("is_activated", static_cast(is_activated_)); + if (!is_activated_) { + std::stringstream message; + message << "Node is not activated."; + diagnostics_initial_pose_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + return; } + // check is_expected_frame_id + const bool is_expected_frame_id = + (initial_pose_msg_ptr->header.frame_id == param_.frame.map_frame); + diagnostics_initial_pose_->addKeyValue("is_expected_frame_id", is_expected_frame_id); + if (!is_expected_frame_id) { + std::stringstream message; + message << "Received initial pose message with frame_id " + << initial_pose_msg_ptr->header.frame_id << ", but expected " << param_.frame.map_frame + << ". Please check the frame_id in the input topic and ensure it is correct."; + diagnostics_initial_pose_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); + return; + } + + initial_pose_buffer_->push_back(initial_pose_msg_ptr); + { // latest_ekf_position_ is also used by callback_timer, so it is necessary to acquire the lock std::lock_guard lock(latest_ekf_position_mtx_); @@ -300,41 +257,83 @@ void NDTScanMatcher::callback_initial_pose( void NDTScanMatcher::callback_regularization_pose( geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr pose_conv_msg_ptr) { + diagnostics_regularization_pose_->clear(); + + diagnostics_regularization_pose_->addKeyValue( + "topic_time_stamp", static_cast(pose_conv_msg_ptr->header.stamp).nanoseconds()); + regularization_pose_buffer_->push_back(pose_conv_msg_ptr); + + diagnostics_regularization_pose_->publish(pose_conv_msg_ptr->header.stamp); } void NDTScanMatcher::callback_sensor_points( sensor_msgs::msg::PointCloud2::ConstSharedPtr sensor_points_msg_in_sensor_frame) { - if (sensor_points_msg_in_sensor_frame->data.empty()) { - RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1, "Empty sensor points!"); - return; + // clear diagnostics + diagnostics_scan_points_->clear(); + + // scan matching + const bool is_succeed_scan_matching = + callback_sensor_points_main(sensor_points_msg_in_sensor_frame); + + // check skipping_publish_num + static size_t skipping_publish_num = 0; + const size_t error_skipping_publish_num = 5; + skipping_publish_num = + ((is_succeed_scan_matching || !is_activated_) ? 0 : (skipping_publish_num + 1)); + diagnostics_scan_points_->addKeyValue("skipping_publish_num", skipping_publish_num); + if (skipping_publish_num >= error_skipping_publish_num) { + std::stringstream message; + message << "skipping_publish_num exceed limit (" << skipping_publish_num << " times)."; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); } + diagnostics_scan_points_->publish(sensor_points_msg_in_sensor_frame->header.stamp); +} + +bool NDTScanMatcher::callback_sensor_points_main( + sensor_msgs::msg::PointCloud2::ConstSharedPtr sensor_points_msg_in_sensor_frame) +{ + const auto exe_start_time = std::chrono::system_clock::now(); + + // check topic_time_stamp const rclcpp::Time sensor_ros_time = sensor_points_msg_in_sensor_frame->header.stamp; - const double lidar_topic_delay_time_sec = (this->now() - sensor_ros_time).seconds(); - (*state_ptr_)["lidar_topic_delay_time_sec"] = std::to_string(lidar_topic_delay_time_sec); + diagnostics_scan_points_->addKeyValue("topic_time_stamp", sensor_ros_time.nanoseconds()); + + // check sensor_points_size + const size_t sensor_points_size = sensor_points_msg_in_sensor_frame->width; + diagnostics_scan_points_->addKeyValue("sensor_points_size", sensor_points_size); + if (sensor_points_size == 0) { + std::stringstream message; + message << "Sensor points is empty."; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + return false; + } - if (lidar_topic_delay_time_sec > param_.validation.lidar_topic_timeout_sec) { - RCLCPP_WARN( - this->get_logger(), - "The LiDAR topic is experiencing latency. The delay time is %lf[sec] (the tolerance is " - "%lf[sec])", - lidar_topic_delay_time_sec, param_.validation.lidar_topic_timeout_sec); + // check sensor_points_delay_time_sec + const double sensor_points_delay_time_sec = + (this->now() - sensor_points_msg_in_sensor_frame->header.stamp).seconds(); + diagnostics_scan_points_->addKeyValue( + "sensor_points_delay_time_sec", sensor_points_delay_time_sec); + if (sensor_points_delay_time_sec > param_.validation.lidar_topic_timeout_sec) { + std::stringstream message; + message << "sensor points is experiencing latency." + << "The delay time is " << sensor_points_delay_time_sec << "[sec] " + << "(the tolerance is " << param_.validation.lidar_topic_timeout_sec << "[sec])."; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); // If the delay time of the LiDAR topic exceeds the delay compensation time of ekf_localizer, // even if further processing continues, the estimated result will be rejected by ekf_localizer. // Therefore, it would be acceptable to exit the function here. // However, for now, we will continue the processing as it is. - // return; + // return false; } - // mutex ndt_ptr_ - std::lock_guard lock(ndt_ptr_mtx_); - - const auto exe_start_time = std::chrono::system_clock::now(); - // preprocess input pointcloud pcl::shared_ptr> sensor_points_in_sensor_frame( new pcl::PointCloud); @@ -343,34 +342,73 @@ void NDTScanMatcher::callback_sensor_points( const std::string & sensor_frame = sensor_points_msg_in_sensor_frame->header.frame_id; pcl::fromROSMsg(*sensor_points_msg_in_sensor_frame, *sensor_points_in_sensor_frame); - transform_sensor_measurement( - sensor_frame, param_.frame.base_frame, sensor_points_in_sensor_frame, - sensor_points_in_baselink_frame); - // check max distance of sensor points + // transform sensor points from sensor-frame to base_link + try { + transform_sensor_measurement( + sensor_frame, param_.frame.base_frame, sensor_points_in_sensor_frame, + sensor_points_in_baselink_frame); + } catch (const std::exception & ex) { + std::stringstream message; + message << ex.what() << ". Please publish TF " << sensor_frame << " to " + << param_.frame.base_frame; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); + RCLCPP_ERROR_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); + diagnostics_scan_points_->addKeyValue("is_succeed_transform_sensor_points", false); + return false; + } + diagnostics_scan_points_->addKeyValue("is_succeed_transform_sensor_points", true); + + // check sensor_points_max_distance double max_distance = 0.0; for (const auto & point : sensor_points_in_baselink_frame->points) { const double distance = std::hypot(point.x, point.y, point.z); max_distance = std::max(max_distance, distance); } + + diagnostics_scan_points_->addKeyValue("sensor_points_max_distance", max_distance); if (max_distance < param_.sensor_points.required_distance) { - RCLCPP_WARN_STREAM( - this->get_logger(), "Max distance of sensor points = " - << std::fixed << std::setprecision(3) << max_distance << " [m] < " - << param_.sensor_points.required_distance << " [m]"); - return; + std::stringstream message; + message << "Max distance of sensor points = " << std::fixed << std::setprecision(3) + << max_distance << " [m] < " << param_.sensor_points.required_distance << " [m]"; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + return false; } + // lock mutex + std::lock_guard lock(ndt_ptr_mtx_); + + // set sensor points to ndt class ndt_ptr_->setInputSource(sensor_points_in_baselink_frame); - if (!is_activated_) return; + + // check is_activated + diagnostics_scan_points_->addKeyValue("is_activated", static_cast(is_activated_)); + if (!is_activated_) { + std::stringstream message; + message << "Node is not activated."; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + return false; + } // calculate initial pose std::optional interpolation_result_opt = initial_pose_buffer_->interpolate(sensor_ros_time); - if (!interpolation_result_opt) { - RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1, "No interpolated pose!"); - return; + + // check is_succeed_interpolate_initial_pose + const bool is_succeed_interpolate_initial_pose = (interpolation_result_opt != std::nullopt); + diagnostics_scan_points_->addKeyValue( + "is_succeed_interpolate_initial_pose", is_succeed_interpolate_initial_pose); + if (!is_succeed_interpolate_initial_pose) { + std::stringstream message; + message << "Couldn't interpolate pose. Please check the initial pose topic"; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + return false; } + initial_pose_buffer_->pop_old(sensor_ros_time); const SmartPoseBuffer::InterpolateResult & interpolation_result = interpolation_result_opt.value(); @@ -380,9 +418,15 @@ void NDTScanMatcher::callback_sensor_points( add_regularization_pose(sensor_ros_time); } - if (ndt_ptr_->getInputTarget() == nullptr) { - RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1, "No MAP!"); - return; + // check is_set_map_points + const bool is_set_map_points = (ndt_ptr_->getInputTarget() != nullptr); + diagnostics_scan_points_->addKeyValue("is_set_map_points", is_set_map_points); + if (!is_set_map_points) { + std::stringstream message; + message << "Map points is not set."; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + return false; } // perform ndt scan matching @@ -399,26 +443,65 @@ void NDTScanMatcher::callback_sensor_points( transformation_msg_array.push_back(pose_ros); } - // perform several validations - bool is_ok_iteration_num = - validate_num_iteration(ndt_result.iteration_num, ndt_ptr_->getMaximumIterations()); - const int oscillation_num = count_oscillation(transformation_msg_array); - bool is_local_optimal_solution_oscillation = false; + // check iteration_num + diagnostics_scan_points_->addKeyValue("iteration_num", ndt_result.iteration_num); + const bool is_ok_iteration_num = (ndt_result.iteration_num < ndt_ptr_->getMaximumIterations()); if (!is_ok_iteration_num) { - constexpr int oscillation_threshold = 10; - is_local_optimal_solution_oscillation = (oscillation_num > oscillation_threshold); + std::stringstream message; + message << "The number of iterations has reached its upper limit. The number of iterations: " + << ndt_result.iteration_num << ", Limit: " << ndt_ptr_->getMaximumIterations() << "."; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); } - bool is_ok_converged_param = validate_converged_param( - ndt_result.transform_probability, ndt_result.nearest_voxel_transformation_likelihood); - bool is_converged = is_ok_iteration_num && is_ok_converged_param; - static size_t skipping_publish_num = 0; - if (is_converged) { - skipping_publish_num = 0; + + // check local_optimal_solution_oscillation_num + constexpr int oscillation_num_threshold = 10; + const int oscillation_num = count_oscillation(transformation_msg_array); + diagnostics_scan_points_->addKeyValue("local_optimal_solution_oscillation_num", oscillation_num); + const bool is_local_optimal_solution_oscillation = (oscillation_num > oscillation_num_threshold); + if (is_local_optimal_solution_oscillation) { + std::stringstream message; + message << "There is a possibility of oscillation in a local minimum"; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + } + + // check score + diagnostics_scan_points_->addKeyValue("transform_probability", ndt_result.transform_probability); + diagnostics_scan_points_->addKeyValue( + "nearest_voxel_transformation_likelihood", ndt_result.nearest_voxel_transformation_likelihood); + double score = 0.0; + double score_threshold = 0.0; + if (param_.score_estimation.converged_param_type == ConvergedParamType::TRANSFORM_PROBABILITY) { + score = ndt_result.transform_probability; + score_threshold = param_.score_estimation.converged_param_transform_probability; + } else if ( + param_.score_estimation.converged_param_type == + ConvergedParamType::NEAREST_VOXEL_TRANSFORMATION_LIKELIHOOD) { + score = ndt_result.nearest_voxel_transformation_likelihood; + score_threshold = + param_.score_estimation.converged_param_nearest_voxel_transformation_likelihood; } else { - ++skipping_publish_num; - RCLCPP_WARN(get_logger(), "Not Converged"); + std::stringstream message; + message << "Unknown converged param type. Please check `score_estimation.converged_param_type`"; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); + return false; } + bool is_ok_score = (score > score_threshold); + if (!is_ok_score) { + std::stringstream message; + message << "Score is below the threshold. Score: " << score + << ", Threshold: " << score_threshold; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + RCLCPP_WARN_STREAM(this->get_logger(), message.str()); + } + + // check is_converged + bool is_converged = (is_ok_iteration_num || is_local_optimal_solution_oscillation) && is_ok_score; + // covariance estimation const Eigen::Quaterniond map_to_base_link_quat = Eigen::Quaterniond( result_pose_msg.orientation.w, result_pose_msg.orientation.x, result_pose_msg.orientation.y, @@ -435,10 +518,31 @@ void NDTScanMatcher::callback_sensor_points( ndt_covariance = estimated_covariance; } + // check distance_initial_to_result + const auto distance_initial_to_result = static_cast( + norm(interpolation_result.interpolated_pose.pose.pose.position, result_pose_msg.position)); + diagnostics_scan_points_->addKeyValue("distance_initial_to_result", distance_initial_to_result); + const double warn_distance_initial_to_result = 3.0; + if (distance_initial_to_result > warn_distance_initial_to_result) { + std::stringstream message; + message << "distance_initial_to_result is too large (" << distance_initial_to_result + << " [m])."; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + } + + // check execution_time const auto exe_end_time = std::chrono::system_clock::now(); const auto duration_micro_sec = std::chrono::duration_cast(exe_end_time - exe_start_time).count(); const auto exe_time = static_cast(duration_micro_sec) / 1000.0f; + diagnostics_scan_points_->addKeyValue("execution_time", exe_time); + if (exe_time > param_.validation.critical_upper_bound_exe_time_ms) { + std::stringstream message; + message << "NDT exe time is too long (took " << exe_time << " [ms])."; + diagnostics_scan_points_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + } // publish initial_pose_with_covariance_pub_->publish(interpolation_result.interpolated_pose); @@ -492,18 +596,7 @@ void NDTScanMatcher::callback_sensor_points( make_float32_stamped(sensor_ros_time, no_ground_nearest_voxel_transformation_likelihood)); } - (*state_ptr_)["state"] = "Aligned"; - (*state_ptr_)["transform_probability"] = std::to_string(ndt_result.transform_probability); - (*state_ptr_)["nearest_voxel_transformation_likelihood"] = - std::to_string(ndt_result.nearest_voxel_transformation_likelihood); - (*state_ptr_)["iteration_num"] = std::to_string(ndt_result.iteration_num); - (*state_ptr_)["skipping_publish_num"] = std::to_string(skipping_publish_num); - (*state_ptr_)["oscillation_count"] = std::to_string(oscillation_num); - (*state_ptr_)["is_local_optimal_solution_oscillation"] = - std::to_string(is_local_optimal_solution_oscillation); - (*state_ptr_)["execution_time"] = std::to_string(exe_time); - - publish_diagnostic(); + return is_converged; } void NDTScanMatcher::transform_sensor_measurement( @@ -520,12 +613,7 @@ void NDTScanMatcher::transform_sensor_measurement( try { transform = tf2_buffer_.lookupTransform(target_frame, source_frame, tf2::TimePointZero); } catch (tf2::TransformException & ex) { - RCLCPP_WARN(this->get_logger(), "%s", ex.what()); - RCLCPP_WARN( - this->get_logger(), "Please publish TF %s to %s", target_frame.c_str(), source_frame.c_str()); - // Since there is no clear error handling policy, temporarily return as is. - sensor_points_output_ptr = sensor_points_input_ptr; - return; + throw; } const geometry_msgs::msg::PoseStamped target_to_source_pose_stamped = @@ -638,54 +726,6 @@ void NDTScanMatcher::publish_initial_to_result( make_float32_stamped(sensor_ros_time, initial_to_result_distance_new)); } -bool NDTScanMatcher::validate_num_iteration(const int iter_num, const int max_iter_num) -{ - bool is_ok_iter_num = iter_num < max_iter_num; - if (!is_ok_iter_num) { - RCLCPP_WARN( - get_logger(), - "The number of iterations has reached its upper limit. The number of iterations: %d, Limit: " - "%d", - iter_num, max_iter_num); - } - return is_ok_iter_num; -} - -bool NDTScanMatcher::validate_score( - const double score, const double score_threshold, const std::string & score_name) -{ - bool is_ok_score = score > score_threshold; - if (!is_ok_score) { - RCLCPP_WARN( - get_logger(), "%s is below the threshold. Score: %lf, Threshold: %lf", score_name.c_str(), - score, score_threshold); - } - return is_ok_score; -} - -bool NDTScanMatcher::validate_converged_param( - const double & transform_probability, const double & nearest_voxel_transformation_likelihood) -{ - bool is_ok_converged_param = false; - if (param_.score_estimation.converged_param_type == ConvergedParamType::TRANSFORM_PROBABILITY) { - is_ok_converged_param = validate_score( - transform_probability, param_.score_estimation.converged_param_transform_probability, - "Transform Probability"); - } else if ( - param_.score_estimation.converged_param_type == - ConvergedParamType::NEAREST_VOXEL_TRANSFORMATION_LIKELIHOOD) { - is_ok_converged_param = validate_score( - nearest_voxel_transformation_likelihood, - param_.score_estimation.converged_param_nearest_voxel_transformation_likelihood, - "Nearest Voxel Transformation Likelihood"); - } else { - is_ok_converged_param = false; - RCLCPP_ERROR_STREAM_THROTTLE( - this->get_logger(), *this->get_clock(), 1, "Unknown converged param type."); - } - return is_ok_converged_param; -} - int NDTScanMatcher::count_oscillation( const std::vector & result_pose_msg_array) { @@ -744,7 +784,10 @@ std::array NDTScanMatcher::estimate_covariance( rot = find_rotation_matrix_aligning_covariance_to_principal_axes( ndt_result.hessian.inverse().block(0, 0, 2, 2)); } catch (const std::exception & e) { - RCLCPP_WARN(get_logger(), "Error in Eigen solver: %s", e.what()); + std::stringstream message; + message << "Error in Eigen solver: " << e.what(); + RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); + return param_.covariance.output_pose_covariance; } @@ -822,23 +865,56 @@ void NDTScanMatcher::add_regularization_pose(const rclcpp::Time & sensor_ros_tim interpolation_result_opt.value(); const Eigen::Matrix4f pose = pose_to_matrix4f(interpolation_result.interpolated_pose.pose.pose); ndt_ptr_->setRegularizationPose(pose); - RCLCPP_DEBUG_STREAM(get_logger(), "Regularization pose is set to NDT"); } void NDTScanMatcher::service_trigger_node( const std_srvs::srv::SetBool::Request::SharedPtr req, std_srvs::srv::SetBool::Response::SharedPtr res) { + const rclcpp::Time ros_time_now = this->now(); + + diagnostics_trigger_node_->clear(); + diagnostics_trigger_node_->addKeyValue("service_call_time_stamp", ros_time_now.nanoseconds()); + is_activated_ = req->data; if (is_activated_) { initial_pose_buffer_->clear(); } res->success = true; + + diagnostics_trigger_node_->addKeyValue("is_activated", static_cast(is_activated_)); + diagnostics_trigger_node_->addKeyValue("is_succeed_service", res->success); + diagnostics_trigger_node_->publish(ros_time_now); } void NDTScanMatcher::service_ndt_align( const tier4_localization_msgs::srv::PoseWithCovarianceStamped::Request::SharedPtr req, tier4_localization_msgs::srv::PoseWithCovarianceStamped::Response::SharedPtr res) +{ + const rclcpp::Time ros_time_now = this->now(); + + diagnostics_ndt_align_->clear(); + + diagnostics_ndt_align_->addKeyValue("service_call_time_stamp", ros_time_now.nanoseconds()); + + service_ndt_align_main(req, res); + + // check is_succeed_service + bool is_succeed_service = res->success; + diagnostics_ndt_align_->addKeyValue("is_succeed_service", is_succeed_service); + if (!is_succeed_service) { + std::stringstream message; + message << "ndt_align_service is failed."; + diagnostics_ndt_align_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + } + + diagnostics_ndt_align_->publish(ros_time_now); +} + +void NDTScanMatcher::service_ndt_align_main( + const tier4_localization_msgs::srv::PoseWithCovarianceStamped::Request::SharedPtr req, + tier4_localization_msgs::srv::PoseWithCovarianceStamped::Response::SharedPtr res) { // get TF from pose_frame to map_frame const std::string & target_frame = param_.frame.map_frame; @@ -851,32 +927,50 @@ void NDTScanMatcher::service_ndt_align( // Note: Up to AWSIMv1.1.0, there is a known bug where the GNSS frame_id is incorrectly set to // "gnss_link" instead of "map". The ndt_align is designed to return identity when this issue // occurs. However, in the future, converting to a non-existent frame_id should be prohibited. - RCLCPP_WARN(this->get_logger(), "%s", ex.what()); - RCLCPP_WARN( - this->get_logger(), "Please publish TF %s to %s", target_frame.c_str(), source_frame.c_str()); - transform_s2t.header.stamp = get_clock()->now(); - transform_s2t.header.frame_id = target_frame; - transform_s2t.child_frame_id = source_frame; - transform_s2t.transform = tf2::toMsg(tf2::Transform::getIdentity()); + + diagnostics_ndt_align_->addKeyValue("is_succeed_transform_initial_pose", false); + + std::stringstream message; + message << "Please publish TF " << target_frame.c_str() << " to " << source_frame.c_str(); + diagnostics_ndt_align_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str()); + RCLCPP_ERROR_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); + res->success = false; + return; } + diagnostics_ndt_align_->addKeyValue("is_succeed_transform_initial_pose", true); // transform pose_frame to map_frame const auto initial_pose_msg_in_map_frame = transform(req->pose_with_covariance, transform_s2t); - map_update_module_->update_map(initial_pose_msg_in_map_frame.pose.pose.position); + map_update_module_->update_map( + initial_pose_msg_in_map_frame.pose.pose.position, diagnostics_ndt_align_); // mutex Map std::lock_guard lock(ndt_ptr_mtx_); - if (ndt_ptr_->getInputTarget() == nullptr) { + // check is_set_map_points + bool is_set_map_points = (ndt_ptr_->getInputTarget() != nullptr); + diagnostics_ndt_align_->addKeyValue("is_set_map_points", is_set_map_points); + if (!is_set_map_points) { + std::stringstream message; + message << "No InputTarget. Please check the map file and the map_loader service"; + diagnostics_ndt_align_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); res->success = false; - RCLCPP_WARN( - get_logger(), "No InputTarget. Please check the map file and the map_loader service"); return; } - if (ndt_ptr_->getInputSource() == nullptr) { + // check is_set_sensor_points + bool is_set_sensor_points = (ndt_ptr_->getInputSource() != nullptr); + diagnostics_ndt_align_->addKeyValue("is_set_sensor_points", is_set_sensor_points); + if (!is_set_sensor_points) { + std::stringstream message; + message << "No InputSource. Please check the input lidar topic"; + diagnostics_ndt_align_->updateLevelAndMessage( + diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); + RCLCPP_WARN_STREAM_THROTTLE(this->get_logger(), *this->get_clock(), 1000, message.str()); res->success = false; - RCLCPP_WARN(get_logger(), "No InputSource. Please check the input lidar topic"); return; } @@ -899,34 +993,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>(); @@ -940,16 +1020,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); @@ -972,22 +1049,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>(); @@ -1007,7 +1075,10 @@ geometry_msgs::msg::PoseWithCovarianceStamped NDTScanMatcher::align_pose( result_pose_with_cov_msg.pose.pose = best_particle_ptr->result_pose; output_pose_with_cov_to_log(get_logger(), "align_pose_output", result_pose_with_cov_msg); - RCLCPP_DEBUG_STREAM(get_logger(), "best_score," << best_particle_ptr->score); + diagnostics_ndt_align_->addKeyValue("best_particle_score", best_particle_ptr->score); return result_pose_with_cov_msg; } + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(NDTScanMatcher) diff --git a/localization/ndt_scan_matcher/src/ndt_scan_matcher_node.cpp b/localization/ndt_scan_matcher/src/ndt_scan_matcher_node.cpp deleted file mode 100644 index 6e2ed022f531e..0000000000000 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_node.cpp +++ /dev/null @@ -1,33 +0,0 @@ -// Copyright 2015-2019 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 "ndt_scan_matcher/ndt_scan_matcher_core.hpp" - -#include - -#include - -int main(int argc, char ** argv) -{ - google::InitGoogleLogging(argv[0]); // NOLINT - google::InstallFailureSignalHandler(); - - rclcpp::init(argc, argv); - auto ndt_scan_matcher = std::make_shared(); - rclcpp::executors::MultiThreadedExecutor exec; - exec.add_node(ndt_scan_matcher); - exec.spin(); - rclcpp::shutdown(); - return 0; -} diff --git a/localization/pose2twist/CMakeLists.txt b/localization/pose2twist/CMakeLists.txt index a2fbbddf7d120..2a586aa9cd049 100644 --- a/localization/pose2twist/CMakeLists.txt +++ b/localization/pose2twist/CMakeLists.txt @@ -4,11 +4,16 @@ project(pose2twist) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_executable(pose2twist - src/pose2twist_node.cpp +ament_auto_add_library(${PROJECT_NAME} SHARED src/pose2twist_core.cpp ) +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "Pose2Twist" + EXECUTABLE ${PROJECT_NAME}_node + EXECUTOR SingleThreadedExecutor +) + ament_auto_package( INSTALL_TO_SHARE launch diff --git a/localization/pose2twist/include/pose2twist/pose2twist_core.hpp b/localization/pose2twist/include/pose2twist/pose2twist_core.hpp index c2a39f7e2ed3d..459a62ea5cd13 100644 --- a/localization/pose2twist/include/pose2twist/pose2twist_core.hpp +++ b/localization/pose2twist/include/pose2twist/pose2twist_core.hpp @@ -24,7 +24,7 @@ class Pose2Twist : public rclcpp::Node { public: - Pose2Twist(); + explicit Pose2Twist(const rclcpp::NodeOptions & options); ~Pose2Twist() = default; private: diff --git a/localization/pose2twist/launch/pose2twist.launch.xml b/localization/pose2twist/launch/pose2twist.launch.xml index a0fae57a163e6..57a41dbfcf017 100644 --- a/localization/pose2twist/launch/pose2twist.launch.xml +++ b/localization/pose2twist/launch/pose2twist.launch.xml @@ -2,7 +2,7 @@ - + diff --git a/localization/pose2twist/package.xml b/localization/pose2twist/package.xml index 16c49bb51c218..07e445c72978c 100644 --- a/localization/pose2twist/package.xml +++ b/localization/pose2twist/package.xml @@ -19,6 +19,7 @@ geometry_msgs rclcpp + rclcpp_components tf2_geometry_msgs tier4_debug_msgs diff --git a/localization/pose2twist/src/pose2twist_core.cpp b/localization/pose2twist/src/pose2twist_core.cpp index a321a06122816..4b98ec6c81ad4 100644 --- a/localization/pose2twist/src/pose2twist_core.cpp +++ b/localization/pose2twist/src/pose2twist_core.cpp @@ -24,7 +24,7 @@ #include #include -Pose2Twist::Pose2Twist() : Node("pose2twist_core") +Pose2Twist::Pose2Twist(const rclcpp::NodeOptions & options) : rclcpp::Node("pose2twist", options) { using std::placeholders::_1; @@ -129,3 +129,6 @@ void Pose2Twist::callbackPose(geometry_msgs::msg::PoseStamped::SharedPtr pose_ms angular_z_msg.data = twist_msg.twist.angular.z; angular_z_pub_->publish(angular_z_msg); } + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(Pose2Twist) diff --git a/localization/pose2twist/src/pose2twist_node.cpp b/localization/pose2twist/src/pose2twist_node.cpp deleted file mode 100644 index 81f98461ecffd..0000000000000 --- a/localization/pose2twist/src/pose2twist_node.cpp +++ /dev/null @@ -1,29 +0,0 @@ -// Copyright 2015-2019 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 "pose2twist/pose2twist_core.hpp" - -#include - -#include - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - - rclcpp::spin(std::make_shared()); - rclcpp::shutdown(); - - return 0; -} diff --git a/localization/pose_estimator_arbiter/CMakeLists.txt b/localization/pose_estimator_arbiter/CMakeLists.txt index 9a47b654a6ab4..eefb7fc9a6879 100644 --- a/localization/pose_estimator_arbiter/CMakeLists.txt +++ b/localization/pose_estimator_arbiter/CMakeLists.txt @@ -4,29 +4,23 @@ project(pose_estimator_arbiter) find_package(autoware_cmake REQUIRED) autoware_package() -find_package(glog REQUIRED) - find_package(PCL REQUIRED COMPONENTS common) include_directories(SYSTEM ${PCL_INCLUDE_DIRS}) -# ============================== -# switch rule library -ament_auto_add_library(switch_rule - SHARED - src/pose_estimator_arbiter/switch_rule/enable_all_rule.cpp -) -target_include_directories(switch_rule PUBLIC src) - # ============================== # pose estimator arbiter node -ament_auto_add_executable(${PROJECT_NAME} +ament_auto_add_library(${PROJECT_NAME} SHARED src/pose_estimator_arbiter/pose_estimator_arbiter_core.cpp - src/pose_estimator_arbiter/pose_estimator_arbiter_node.cpp + src/pose_estimator_arbiter/switch_rule/enable_all_rule.cpp ) target_include_directories(${PROJECT_NAME} PUBLIC src) -target_link_libraries(${PROJECT_NAME} switch_rule glog::glog) -# ============================== +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "pose_estimator_arbiter::PoseEstimatorArbiter" + EXECUTABLE ${PROJECT_NAME}_node + EXECUTOR MultiThreadedExecutor +) + if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) @@ -53,6 +47,7 @@ endif() add_subdirectory(example_rule) # ============================== -ament_auto_package(INSTALL_TO_SHARE +ament_auto_package( + INSTALL_TO_SHARE launch ) diff --git a/localization/pose_estimator_arbiter/example_rule/CMakeLists.txt b/localization/pose_estimator_arbiter/example_rule/CMakeLists.txt index 333f92842b860..b2b5a828e42e7 100644 --- a/localization/pose_estimator_arbiter/example_rule/CMakeLists.txt +++ b/localization/pose_estimator_arbiter/example_rule/CMakeLists.txt @@ -7,7 +7,7 @@ ament_auto_add_library(example_rule src/pose_estimator_arbiter/rule_helper/pose_estimator_area.cpp ) target_include_directories(example_rule PUBLIC src example_rule/src) -target_link_libraries(example_rule switch_rule) +target_link_libraries(example_rule pose_estimator_arbiter) # ============================== # define test definition macro @@ -16,7 +16,7 @@ function(add_testcase filepath) string(REGEX REPLACE ".cpp" "" test_name ${filename}) ament_add_gtest(${test_name} ${filepath}) - target_link_libraries("${test_name}" switch_rule example_rule) + target_link_libraries("${test_name}" pose_estimator_arbiter example_rule) target_include_directories(${test_name} PUBLIC src) ament_target_dependencies(${test_name} ${${PROJECT_NAME}_FOUND_BUILD_DEPENDS}) endfunction() diff --git a/localization/pose_estimator_arbiter/launch/pose_estimator_arbiter.launch.xml b/localization/pose_estimator_arbiter/launch/pose_estimator_arbiter.launch.xml index 0a708e3f48988..b5be96fc3ce44 100644 --- a/localization/pose_estimator_arbiter/launch/pose_estimator_arbiter.launch.xml +++ b/localization/pose_estimator_arbiter/launch/pose_estimator_arbiter.launch.xml @@ -3,7 +3,7 @@ - + diff --git a/localization/pose_estimator_arbiter/package.xml b/localization/pose_estimator_arbiter/package.xml index b416d42c8617f..d164086ada87e 100644 --- a/localization/pose_estimator_arbiter/package.xml +++ b/localization/pose_estimator_arbiter/package.xml @@ -16,11 +16,11 @@ diagnostic_msgs geometry_msgs lanelet2_extension - libgoogle-glog-dev magic_enum pcl_conversions pcl_ros pluginlib + rclcpp_components sensor_msgs std_msgs std_srvs @@ -29,9 +29,6 @@ visualization_msgs yabloc_particle_filter - rclcpp - rclcpp_components - ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter.hpp b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter.hpp index 9e67dfc063964..54dac6ac254c1 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter.hpp +++ b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter.hpp @@ -47,7 +47,7 @@ class PoseEstimatorArbiter : public rclcpp::Node using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray; public: - PoseEstimatorArbiter(); + explicit PoseEstimatorArbiter(const rclcpp::NodeOptions & options); private: // Set of running pose estimators specified by ros param `pose_sources` diff --git a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter_core.cpp b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter_core.cpp index 4fc3fd9b914a6..67c555227976d 100644 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter_core.cpp +++ b/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter_core.cpp @@ -42,8 +42,8 @@ static std::unordered_set parse_estimator_name_args( return running_estimator_list; } -PoseEstimatorArbiter::PoseEstimatorArbiter() -: Node("pose_estimator_arbiter"), +PoseEstimatorArbiter::PoseEstimatorArbiter(const rclcpp::NodeOptions & options) +: rclcpp::Node("pose_estimator_arbiter", options), running_estimator_list_(parse_estimator_name_args( declare_parameter>("pose_sources"), get_logger())), logger_configure_(std::make_unique(this)) @@ -211,3 +211,6 @@ void PoseEstimatorArbiter::on_timer() } } // namespace pose_estimator_arbiter + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(pose_estimator_arbiter::PoseEstimatorArbiter) 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 deleted file mode 100644 index e48507948520b..0000000000000 --- a/localization/pose_estimator_arbiter/src/pose_estimator_arbiter/pose_estimator_arbiter_node.cpp +++ /dev/null @@ -1,31 +0,0 @@ -// Copyright 2023 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 "pose_estimator_arbiter/pose_estimator_arbiter.hpp" - -#include - -int main(int argc, char * argv[]) -{ - google::InitGoogleLogging(argv[0]); - google::InstallFailureSignalHandler(); - - rclcpp::init(argc, argv); - auto node = std::make_shared(); - rclcpp::executors::MultiThreadedExecutor executor; - executor.add_node(node); - executor.spin(); - rclcpp::shutdown(); - return 0; -} diff --git a/localization/pose_initializer/CMakeLists.txt b/localization/pose_initializer/CMakeLists.txt index 81a60a1d6b717..08d5bb47fca09 100644 --- a/localization/pose_initializer/CMakeLists.txt +++ b/localization/pose_initializer/CMakeLists.txt @@ -4,8 +4,7 @@ project(pose_initializer) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_executable(pose_initializer_node - src/pose_initializer/pose_initializer_node.cpp +ament_auto_add_library(${PROJECT_NAME} SHARED src/pose_initializer/pose_initializer_core.cpp src/pose_initializer/gnss_module.cpp src/pose_initializer/ndt_module.cpp @@ -15,6 +14,12 @@ ament_auto_add_executable(pose_initializer_node src/pose_initializer/ndt_localization_trigger_module.cpp ) +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "PoseInitializer" + EXECUTABLE ${PROJECT_NAME}_node + EXECUTOR MultiThreadedExecutor +) + if(BUILD_TESTING) function(add_testcase filepath) get_filename_component(filename ${filepath} NAME) @@ -30,7 +35,8 @@ if(BUILD_TESTING) add_testcase(test/test_copy_vector_to_array.cpp) endif() -ament_auto_package(INSTALL_TO_SHARE +ament_auto_package( + INSTALL_TO_SHARE launch config ) diff --git a/localization/pose_initializer/README.md b/localization/pose_initializer/README.md index 7006becf00c2f..36cc92e1d235b 100644 --- a/localization/pose_initializer/README.md +++ b/localization/pose_initializer/README.md @@ -17,9 +17,9 @@ This node depends on the map height fitter library. ### Services -| Name | Type | Description | -| -------------------------- | --------------------------------------------------- | --------------------- | -| `/localization/initialize` | autoware_adapi_v1_msgs::srv::InitializeLocalization | initial pose from api | +| Name | Type | Description | +| -------------------------- | ---------------------------------------------------- | --------------------- | +| `/localization/initialize` | tier4_localization_msgs::srv::InitializeLocalization | initial pose from api | ### Clients @@ -46,3 +46,86 @@ This node depends on the map height fitter library. This `pose_initializer` is used via default AD API. For detailed description of the API description, please refer to [the description of `default_ad_api`](https://github.com/autowarefoundation/autoware.universe/blob/main/system/default_ad_api/document/localization.md). drawing + +## Initialize pose via CLI + +### Using the GNSS estimated position + +```bash +ros2 service call /localization/initialize tier4_localization_msgs/srv/InitializeLocalization +``` + +The GNSS estimated position is used as the initial guess, and the localization algorithm automatically estimates a more accurate position. + +### Using the input position + +```bash +ros2 service call /localization/initialize tier4_localization_msgs/srv/InitializeLocalization " +pose_with_covariance: + - header: + frame_id: map + pose: + pose: + position: + x: 89571.1640625 + y: 42301.1875 + z: -3.1565165519714355 + orientation: + x: 0.0 + y: 0.0 + z: 0.28072773940524687 + w: 0.9597874433062874 + covariance: [0.25, 0, 0, 0, 0, 0, 0, 0.25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.06853891909122467] +method: 0 +" +``` + +The input position is used as the initial guess, and the localization algorithm automatically estimates a more accurate position. + +### Direct initial position set + +```bash +ros2 service call /localization/initialize tier4_localization_msgs/srv/InitializeLocalization " +pose_with_covariance: + - header: + frame_id: map + pose: + pose: + position: + x: 89571.1640625 + y: 42301.1875 + z: -3.1565165519714355 + orientation: + x: 0.0 + y: 0.0 + z: 0.28072773940524687 + w: 0.9597874433062874 + covariance: [0.25, 0, 0, 0, 0, 0, 0, 0.25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.06853891909122467] +method: 1 +" +``` + +The initial position is set directly by the input position without going through localization algorithm. + +### Via ros2 topic pub + +```bash +ros2 topic pub --once /initialpose geometry_msgs/msg/PoseWithCovarianceStamped " +header: + frame_id: map +pose: + pose: + position: + x: 89571.1640625 + y: 42301.1875 + z: 0.0 + orientation: + x: 0.0 + y: 0.0 + z: 0.28072773940524687 + w: 0.9597874433062874 +" +``` + +It behaves the same as "initialpose (from rviz)". +The position.z and the covariance will be overwritten by [ad_api_adaptors](https://github.com/autowarefoundation/autoware.universe/tree/main/system/default_ad_api_helpers/ad_api_adaptors), so there is no need to input them. diff --git a/localization/pose_initializer/launch/pose_initializer.launch.xml b/localization/pose_initializer/launch/pose_initializer.launch.xml index 3e4911e2c2936..2ffdebf39c474 100644 --- a/localization/pose_initializer/launch/pose_initializer.launch.xml +++ b/localization/pose_initializer/launch/pose_initializer.launch.xml @@ -9,7 +9,7 @@ - + diff --git a/localization/pose_initializer/package.xml b/localization/pose_initializer/package.xml index 85c9c26bd6c8c..58968828bc2fa 100644 --- a/localization/pose_initializer/package.xml +++ b/localization/pose_initializer/package.xml @@ -25,6 +25,7 @@ map_height_fitter motion_utils rclcpp + rclcpp_components std_srvs tier4_autoware_utils tier4_localization_msgs diff --git a/localization/pose_initializer/src/pose_initializer/pose_initializer_core.cpp b/localization/pose_initializer/src/pose_initializer/pose_initializer_core.cpp index bc86b5476dcca..2fc7d61890837 100644 --- a/localization/pose_initializer/src/pose_initializer/pose_initializer_core.cpp +++ b/localization/pose_initializer/src/pose_initializer/pose_initializer_core.cpp @@ -23,9 +23,11 @@ #include "yabloc_module.hpp" #include +#include #include -PoseInitializer::PoseInitializer() : Node("pose_initializer") +PoseInitializer::PoseInitializer(const rclcpp::NodeOptions & options) +: rclcpp::Node("pose_initializer", options) { const auto node = component_interface_utils::NodeAdaptor(this); group_srv_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); @@ -79,7 +81,7 @@ PoseInitializer::PoseInitializer() : Node("pose_initializer") initial_pose.orientation.z = initial_pose_array[5]; initial_pose.orientation.w = initial_pose_array[6]; - set_user_defined_initial_pose(initial_pose); + set_user_defined_initial_pose(initial_pose, true); } } } @@ -114,11 +116,12 @@ void PoseInitializer::change_node_trigger(bool flag, bool need_spin) } } -void PoseInitializer::set_user_defined_initial_pose(const geometry_msgs::msg::Pose initial_pose) +void PoseInitializer::set_user_defined_initial_pose( + const geometry_msgs::msg::Pose initial_pose, bool need_spin) { try { change_state(State::Message::INITIALIZING); - change_node_trigger(false, true); + change_node_trigger(false, need_spin); PoseWithCovarianceStamped pose; pose.header.frame_id = "map"; @@ -127,7 +130,7 @@ void PoseInitializer::set_user_defined_initial_pose(const geometry_msgs::msg::Po pose.pose.covariance = output_pose_covariance_; pub_reset_->publish(pose); - change_node_trigger(true, true); + change_node_trigger(true, need_spin); change_state(State::Message::INITIALIZED); RCLCPP_INFO(get_logger(), "Set user defined initial pose"); @@ -147,25 +150,52 @@ void PoseInitializer::on_initialize( Initialize::Service::Response::ERROR_UNSAFE, "The vehicle is not stopped."); } try { - change_state(State::Message::INITIALIZING); - change_node_trigger(false, false); - - auto pose = req->pose.empty() ? get_gnss_pose() : req->pose.front(); - if (ndt_) { - pose = ndt_->align_pose(pose); - } else if (yabloc_) { - // If both the NDT and YabLoc initializer are enabled, prioritize NDT as it offers more - // accuracy pose. - pose = yabloc_->align_pose(pose); - } - pose.pose.covariance = output_pose_covariance_; - pub_reset_->publish(pose); + if (req->method == Initialize::Service::Request::AUTO) { + change_state(State::Message::INITIALIZING); + change_node_trigger(false, false); + + auto pose = + req->pose_with_covariance.empty() ? get_gnss_pose() : req->pose_with_covariance.front(); + if (ndt_) { + pose = ndt_->align_pose(pose); + } else if (yabloc_) { + // If both the NDT and YabLoc initializer are enabled, prioritize NDT as it offers more + // accuracy pose. + pose = yabloc_->align_pose(pose); + } + pose.pose.covariance = output_pose_covariance_; + pub_reset_->publish(pose); + + change_node_trigger(true, false); + res->status.success = true; + change_state(State::Message::INITIALIZED); + + } else if (req->method == Initialize::Service::Request::DIRECT) { + if (req->pose_with_covariance.empty()) { + std::stringstream message; + message << "No input pose_with_covariance. If you want to use DIRECT method, please input " + "pose_with_covariance."; + RCLCPP_ERROR(get_logger(), message.str().c_str()); + throw ServiceException( + autoware_common_msgs::msg::ResponseStatus::PARAMETER_ERROR, message.str()); + } + auto pose = req->pose_with_covariance.front().pose.pose; + set_user_defined_initial_pose(pose, false); + res->status.success = true; - change_node_trigger(true, false); - res->status.success = true; - change_state(State::Message::INITIALIZED); + } else { + std::stringstream message; + message << "Unknown method type (=" << std::to_string(req->method) << ")"; + RCLCPP_ERROR(get_logger(), message.str().c_str()); + throw ServiceException( + autoware_common_msgs::msg::ResponseStatus::PARAMETER_ERROR, message.str()); + } } catch (const ServiceException & error) { - res->status = error.status(); + autoware_adapi_v1_msgs::msg::ResponseStatus respose_status; + respose_status = error.status(); + res->status.success = respose_status.success; + res->status.code = respose_status.code; + res->status.message = respose_status.message; change_state(State::Message::UNINITIALIZED); } } @@ -180,3 +210,6 @@ geometry_msgs::msg::PoseWithCovarianceStamped PoseInitializer::get_gnss_pose() throw ServiceException( Initialize::Service::Response::ERROR_GNSS_SUPPORT, "GNSS is not supported."); } + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(PoseInitializer) diff --git a/localization/pose_initializer/src/pose_initializer/pose_initializer_core.hpp b/localization/pose_initializer/src/pose_initializer/pose_initializer_core.hpp index 623cfe50307f5..eeba71b90129b 100644 --- a/localization/pose_initializer/src/pose_initializer/pose_initializer_core.hpp +++ b/localization/pose_initializer/src/pose_initializer/pose_initializer_core.hpp @@ -34,7 +34,7 @@ class NdtLocalizationTriggerModule; class PoseInitializer : public rclcpp::Node { public: - PoseInitializer(); + explicit PoseInitializer(const rclcpp::NodeOptions & options); ~PoseInitializer(); private: @@ -60,7 +60,8 @@ class PoseInitializer : public rclcpp::Node double stop_check_duration_; void change_node_trigger(bool flag, bool need_spin = false); - void set_user_defined_initial_pose(const geometry_msgs::msg::Pose initial_pose); + void set_user_defined_initial_pose( + const geometry_msgs::msg::Pose initial_pose, bool need_spin = false); void change_state(State::Message::_state_type state); void on_initialize( const Initialize::Service::Request::SharedPtr req, diff --git a/localization/pose_initializer/src/pose_initializer/pose_initializer_node.cpp b/localization/pose_initializer/src/pose_initializer/pose_initializer_node.cpp deleted file mode 100644 index c5b31c4e37ccd..0000000000000 --- a/localization/pose_initializer/src/pose_initializer/pose_initializer_node.cpp +++ /dev/null @@ -1,29 +0,0 @@ -// Copyright 2020 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 "pose_initializer_core.hpp" - -#include - -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(); - return 0; -} diff --git a/localization/pose_instability_detector/CMakeLists.txt b/localization/pose_instability_detector/CMakeLists.txt index 5270df636d791..c6f94ab7df16e 100644 --- a/localization/pose_instability_detector/CMakeLists.txt +++ b/localization/pose_instability_detector/CMakeLists.txt @@ -4,14 +4,19 @@ project(pose_instability_detector) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_executable(pose_instability_detector - src/main.cpp +ament_auto_add_library(${PROJECT_NAME} SHARED src/pose_instability_detector.cpp ) +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "PoseInstabilityDetector" + EXECUTABLE ${PROJECT_NAME}_node + EXECUTOR SingleThreadedExecutor +) + if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) - ament_auto_add_gtest(test_pose_instability_detector + ament_auto_add_gtest(test_${PROJECT_NAME} test/test.cpp src/pose_instability_detector.cpp ) @@ -19,6 +24,6 @@ endif() ament_auto_package( INSTALL_TO_SHARE - launch - config + launch + config ) diff --git a/localization/pose_instability_detector/launch/pose_instability_detector.launch.xml b/localization/pose_instability_detector/launch/pose_instability_detector.launch.xml index 4a390ee2854d7..5ebe7d7e429e0 100644 --- a/localization/pose_instability_detector/launch/pose_instability_detector.launch.xml +++ b/localization/pose_instability_detector/launch/pose_instability_detector.launch.xml @@ -6,7 +6,7 @@ - + diff --git a/localization/pose_instability_detector/package.xml b/localization/pose_instability_detector/package.xml index bf57e5589b747..d658d1c2d437f 100644 --- a/localization/pose_instability_detector/package.xml +++ b/localization/pose_instability_detector/package.xml @@ -22,6 +22,7 @@ geometry_msgs nav_msgs rclcpp + rclcpp_components tf2 tf2_geometry_msgs tier4_autoware_utils diff --git a/localization/pose_instability_detector/src/main.cpp b/localization/pose_instability_detector/src/main.cpp deleted file mode 100644 index 34e679e86730f..0000000000000 --- a/localization/pose_instability_detector/src/main.cpp +++ /dev/null @@ -1,26 +0,0 @@ -// Copyright 2023- 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 "pose_instability_detector.hpp" - -#include - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - auto pose_instability_detector = std::make_shared(); - rclcpp::spin(pose_instability_detector); - rclcpp::shutdown(); - return 0; -} diff --git a/localization/pose_instability_detector/src/pose_instability_detector.cpp b/localization/pose_instability_detector/src/pose_instability_detector.cpp index afb7d6e007db2..c2bce6a3db288 100644 --- a/localization/pose_instability_detector/src/pose_instability_detector.cpp +++ b/localization/pose_instability_detector/src/pose_instability_detector.cpp @@ -23,7 +23,7 @@ #include PoseInstabilityDetector::PoseInstabilityDetector(const rclcpp::NodeOptions & options) -: Node("pose_instability_detector", options), +: rclcpp::Node("pose_instability_detector", options), threshold_diff_position_x_(this->declare_parameter("threshold_diff_position_x")), threshold_diff_position_y_(this->declare_parameter("threshold_diff_position_y")), threshold_diff_position_z_(this->declare_parameter("threshold_diff_position_z")), @@ -174,3 +174,6 @@ void PoseInstabilityDetector::callback_timer() prev_odometry_ = latest_odometry_; twist_buffer_.clear(); } + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(PoseInstabilityDetector) diff --git a/localization/stop_filter/CMakeLists.txt b/localization/stop_filter/CMakeLists.txt index 97a0443195ae5..4776a1f4967b2 100644 --- a/localization/stop_filter/CMakeLists.txt +++ b/localization/stop_filter/CMakeLists.txt @@ -4,11 +4,15 @@ project(stop_filter) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_executable(stop_filter - src/stop_filter_node.cpp +ament_auto_add_library(${PROJECT_NAME} SHARED src/stop_filter.cpp ) -ament_target_dependencies(stop_filter) + +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "StopFilter" + EXECUTABLE ${PROJECT_NAME}_node + EXECUTOR SingleThreadedExecutor +) ament_auto_package( INSTALL_TO_SHARE diff --git a/localization/stop_filter/include/stop_filter/stop_filter.hpp b/localization/stop_filter/include/stop_filter/stop_filter.hpp index 3c2b91590234f..24145a7920d91 100644 --- a/localization/stop_filter/include/stop_filter/stop_filter.hpp +++ b/localization/stop_filter/include/stop_filter/stop_filter.hpp @@ -37,7 +37,7 @@ class StopFilter : public rclcpp::Node { public: - StopFilter(const std::string & node_name, const rclcpp::NodeOptions & options); + explicit StopFilter(const rclcpp::NodeOptions & options); private: rclcpp::Publisher::SharedPtr pub_odom_; //!< @brief odom publisher diff --git a/localization/stop_filter/launch/stop_filter.launch.xml b/localization/stop_filter/launch/stop_filter.launch.xml index 0ea92d26c9677..c53b37efc9954 100644 --- a/localization/stop_filter/launch/stop_filter.launch.xml +++ b/localization/stop_filter/launch/stop_filter.launch.xml @@ -3,7 +3,7 @@ - + diff --git a/localization/stop_filter/package.xml b/localization/stop_filter/package.xml index 83eaf1b9fa821..2e6d5c4f8bbe1 100644 --- a/localization/stop_filter/package.xml +++ b/localization/stop_filter/package.xml @@ -21,6 +21,7 @@ geometry_msgs nav_msgs rclcpp + rclcpp_components tf2 tier4_debug_msgs diff --git a/localization/stop_filter/src/stop_filter.cpp b/localization/stop_filter/src/stop_filter.cpp index ac0960b8cb67b..4d6b2c6240867 100644 --- a/localization/stop_filter/src/stop_filter.cpp +++ b/localization/stop_filter/src/stop_filter.cpp @@ -24,8 +24,8 @@ using std::placeholders::_1; -StopFilter::StopFilter(const std::string & node_name, const rclcpp::NodeOptions & node_options) -: rclcpp::Node(node_name, node_options) +StopFilter::StopFilter(const rclcpp::NodeOptions & node_options) +: rclcpp::Node("stop_filter", node_options) { vx_threshold_ = declare_parameter("vx_threshold"); wz_threshold_ = declare_parameter("wz_threshold"); @@ -57,3 +57,6 @@ void StopFilter::callbackOdometry(const nav_msgs::msg::Odometry::SharedPtr msg) pub_stop_flag_->publish(stop_flag_msg); pub_odom_->publish(odom_msg); } + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(StopFilter) diff --git a/localization/stop_filter/src/stop_filter_node.cpp b/localization/stop_filter/src/stop_filter_node.cpp deleted file mode 100644 index 9748214828de2..0000000000000 --- a/localization/stop_filter/src/stop_filter_node.cpp +++ /dev/null @@ -1,28 +0,0 @@ -// Copyright 2021 TierIV -// -// 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 "stop_filter/stop_filter.hpp" - -#include - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - rclcpp::NodeOptions node_options; - auto node = std::make_shared("stop_filter", node_options); - - rclcpp::spin(node); - - return 0; -} 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); diff --git a/localization/twist2accel/CMakeLists.txt b/localization/twist2accel/CMakeLists.txt index 59f23eacb2fb3..9178bf02288a8 100644 --- a/localization/twist2accel/CMakeLists.txt +++ b/localization/twist2accel/CMakeLists.txt @@ -4,11 +4,15 @@ project(twist2accel) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_executable(twist2accel - src/twist2accel_node.cpp +ament_auto_add_library(${PROJECT_NAME} SHARED src/twist2accel.cpp ) -ament_target_dependencies(twist2accel) + +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "Twist2Accel" + EXECUTABLE ${PROJECT_NAME}_node + EXECUTOR SingleThreadedExecutor +) ament_auto_package( INSTALL_TO_SHARE diff --git a/localization/twist2accel/include/twist2accel/twist2accel.hpp b/localization/twist2accel/include/twist2accel/twist2accel.hpp index da5f2b4a3b228..0db69890fbfe8 100644 --- a/localization/twist2accel/include/twist2accel/twist2accel.hpp +++ b/localization/twist2accel/include/twist2accel/twist2accel.hpp @@ -40,7 +40,7 @@ class Twist2Accel : public rclcpp::Node { public: - Twist2Accel(const std::string & node_name, const rclcpp::NodeOptions & options); + explicit Twist2Accel(const rclcpp::NodeOptions & options); private: rclcpp::Publisher::SharedPtr diff --git a/localization/twist2accel/launch/twist2accel.launch.xml b/localization/twist2accel/launch/twist2accel.launch.xml index c4c9a3ed50bfc..c534a288aac3e 100644 --- a/localization/twist2accel/launch/twist2accel.launch.xml +++ b/localization/twist2accel/launch/twist2accel.launch.xml @@ -4,7 +4,7 @@ - + diff --git a/localization/twist2accel/package.xml b/localization/twist2accel/package.xml index 08dacf9185769..0dbce08f309ac 100644 --- a/localization/twist2accel/package.xml +++ b/localization/twist2accel/package.xml @@ -21,6 +21,7 @@ geometry_msgs nav_msgs rclcpp + rclcpp_components signal_processing tf2 tier4_debug_msgs diff --git a/localization/twist2accel/src/twist2accel.cpp b/localization/twist2accel/src/twist2accel.cpp index 68019f27e95fe..0af29445bbeb8 100644 --- a/localization/twist2accel/src/twist2accel.cpp +++ b/localization/twist2accel/src/twist2accel.cpp @@ -24,8 +24,8 @@ using std::placeholders::_1; -Twist2Accel::Twist2Accel(const std::string & node_name, const rclcpp::NodeOptions & node_options) -: rclcpp::Node(node_name, node_options) +Twist2Accel::Twist2Accel(const rclcpp::NodeOptions & node_options) +: rclcpp::Node("twist2accel", node_options) { sub_odom_ = create_subscription( "input/odom", 1, std::bind(&Twist2Accel::callbackOdometry, this, _1)); @@ -103,3 +103,6 @@ void Twist2Accel::estimateAccel(const geometry_msgs::msg::TwistStamped::SharedPt pub_accel_->publish(accel_msg); prev_twist_ptr_ = msg; } + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(Twist2Accel) diff --git a/localization/twist2accel/src/twist2accel_node.cpp b/localization/twist2accel/src/twist2accel_node.cpp deleted file mode 100644 index ce8ed31db5c32..0000000000000 --- a/localization/twist2accel/src/twist2accel_node.cpp +++ /dev/null @@ -1,28 +0,0 @@ -// Copyright 2022 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 "twist2accel/twist2accel.hpp" - -#include - -int main(int argc, char ** argv) -{ - rclcpp::init(argc, argv); - rclcpp::NodeOptions node_options; - auto node = std::make_shared("twist2accel", node_options); - - rclcpp::spin(node); - - return 0; -} diff --git a/localization/yabloc/yabloc_common/CMakeLists.txt b/localization/yabloc/yabloc_common/CMakeLists.txt index c8474a85ad963..ca2f28bae7cda 100644 --- a/localization/yabloc/yabloc_common/CMakeLists.txt +++ b/localization/yabloc/yabloc_common/CMakeLists.txt @@ -23,9 +23,6 @@ find_package(Sophus REQUIRED) # because it rewrite CMAKE_NO_SYSTEM_FROM_IMPORTED to TRUE. set(CMAKE_NO_SYSTEM_FROM_IMPORTED FALSE) -# glog -find_package(glog REQUIRED) - # =================================================== # GeographicLib find_package(PkgConfig) @@ -45,7 +42,10 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/static_tf_subscriber.cpp src/extract_line_segments.cpp src/transform_line_segments.cpp - src/color.cpp) + src/color.cpp + src/ground_server/ground_server_core.cpp + src/ground_server/polygon_operation.cpp + src/ll2_decomposer/ll2_decomposer_core.cpp) target_include_directories( ${PROJECT_NAME} PUBLIC include ) @@ -63,23 +63,18 @@ target_link_libraries(${PROJECT_NAME} Geographic ${PCL_LIBRARIES} Sophus::Sophus # =================================================== # Executables # ground_server -set(TARGET ground_server_node) -ament_auto_add_executable(${TARGET} - src/ground_server/ground_server_core.cpp - src/ground_server/ground_server_node.cpp - src/ground_server/polygon_operation.cpp) -target_include_directories(${TARGET} PUBLIC include) -target_include_directories(${TARGET} SYSTEM PRIVATE ${EIGEN3_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS}) -target_link_libraries(${TARGET} ${PCL_LIBRARIES} Sophus::Sophus glog::glog) +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "yabloc::ground_server::GroundServer" + EXECUTABLE yabloc_ground_server_node + EXECUTOR SingleThreadedExecutor +) # ll2_decomposer -set(TARGET ll2_decomposer_node) -ament_auto_add_executable(${TARGET} - src/ll2_decomposer/ll2_decomposer_core.cpp - src/ll2_decomposer/ll2_decomposer_node.cpp) -target_include_directories(${TARGET} PUBLIC include) -target_include_directories(${TARGET} SYSTEM PRIVATE ${EIGEN3_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS}) -target_link_libraries(${TARGET} ${PCL_LIBRARIES}) +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "yabloc::ll2_decomposer::Ll2Decomposer" + EXECUTABLE yabloc_ll2_decomposer_node + EXECUTOR SingleThreadedExecutor +) # =================================================== ament_export_dependencies(PCL Sophus) diff --git a/localization/yabloc/yabloc_common/include/yabloc_common/ground_server/ground_server.hpp b/localization/yabloc/yabloc_common/include/yabloc_common/ground_server/ground_server.hpp index 154507f8195d9..4cc4128ad5a70 100644 --- a/localization/yabloc/yabloc_common/include/yabloc_common/ground_server/ground_server.hpp +++ b/localization/yabloc/yabloc_common/include/yabloc_common/ground_server/ground_server.hpp @@ -57,7 +57,7 @@ class GroundServer : public rclcpp::Node using String = std_msgs::msg::String; using PointCloud2 = sensor_msgs::msg::PointCloud2; using Point = geometry_msgs::msg::Point; - GroundServer(); + explicit GroundServer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); private: const bool force_zero_tilt_; diff --git a/localization/yabloc/yabloc_common/include/yabloc_common/ll2_decomposer/ll2_decomposer.hpp b/localization/yabloc/yabloc_common/include/yabloc_common/ll2_decomposer/ll2_decomposer.hpp index f6e6de6b38fdd..784b3997faffd 100644 --- a/localization/yabloc/yabloc_common/include/yabloc_common/ll2_decomposer/ll2_decomposer.hpp +++ b/localization/yabloc/yabloc_common/include/yabloc_common/ll2_decomposer/ll2_decomposer.hpp @@ -39,7 +39,7 @@ class Ll2Decomposer : public rclcpp::Node using Marker = visualization_msgs::msg::Marker; using MarkerArray = visualization_msgs::msg::MarkerArray; - Ll2Decomposer(); + explicit Ll2Decomposer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); private: rclcpp::Publisher::SharedPtr pub_road_marking_; diff --git a/localization/yabloc/yabloc_common/launch/yabloc_common.launch.xml b/localization/yabloc/yabloc_common/launch/yabloc_common.launch.xml index 48299e880cc9c..29d3da71bce7f 100644 --- a/localization/yabloc/yabloc_common/launch/yabloc_common.launch.xml +++ b/localization/yabloc/yabloc_common/launch/yabloc_common.launch.xml @@ -1,5 +1,7 @@ + + @@ -7,7 +9,7 @@ - + @@ -25,7 +27,7 @@ - + diff --git a/localization/yabloc/yabloc_common/package.xml b/localization/yabloc/yabloc_common/package.xml index 710ec0aeb75f8..caf044660257e 100644 --- a/localization/yabloc/yabloc_common/package.xml +++ b/localization/yabloc/yabloc_common/package.xml @@ -21,9 +21,9 @@ geometry_msgs lanelet2_core lanelet2_extension - libgoogle-glog-dev pcl_conversions rclcpp + rclcpp_components sensor_msgs signal_processing sophus diff --git a/localization/yabloc/yabloc_common/src/extract_line_segments.cpp b/localization/yabloc/yabloc_common/src/extract_line_segments.cpp index 9987c4fbb5e72..9940dca1fd62b 100644 --- a/localization/yabloc/yabloc_common/src/extract_line_segments.cpp +++ b/localization/yabloc/yabloc_common/src/extract_line_segments.cpp @@ -20,12 +20,13 @@ pcl::PointCloud extract_near_line_segments( const pcl::PointCloud & line_segments, const Sophus::SE3f & transform, const float max_range) { - constexpr double sqrt_two = std::sqrt(2); + constexpr double sqrt_two = 1.41421356237309504880; const Eigen::Vector3f pose_vector = transform.translation(); // All line segments contained in a square with max_range on one side must be taken out, // so pick up those that are closer than the **diagonals** of the square. - auto check_intersection = [max_range, pose_vector](const pcl::PointNormal & pn) -> bool { + auto check_intersection = [sqrt_two, max_range, + pose_vector](const pcl::PointNormal & pn) -> bool { const Eigen::Vector3f from = pn.getVector3fMap() - pose_vector; const Eigen::Vector3f to = pn.getNormalVector3fMap() - pose_vector; diff --git a/localization/yabloc/yabloc_common/src/ground_server/ground_server_core.cpp b/localization/yabloc/yabloc_common/src/ground_server/ground_server_core.cpp index 749aa39318923..75d5f8e1f9cbc 100644 --- a/localization/yabloc/yabloc_common/src/ground_server/ground_server_core.cpp +++ b/localization/yabloc/yabloc_common/src/ground_server/ground_server_core.cpp @@ -30,8 +30,8 @@ namespace yabloc::ground_server { -GroundServer::GroundServer() -: Node("ground_server"), +GroundServer::GroundServer(const rclcpp::NodeOptions & options) +: Node("ground_server", options), force_zero_tilt_(declare_parameter("force_zero_tilt")), R(declare_parameter("R")), K(declare_parameter("K")) @@ -248,3 +248,6 @@ GroundServer::GroundPlane GroundServer::estimate_ground(const Point & point) } } // namespace yabloc::ground_server + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(yabloc::ground_server::GroundServer) 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 deleted file mode 100644 index ff50eeee0421d..0000000000000 --- a/localization/yabloc/yabloc_common/src/ground_server/ground_server_node.cpp +++ /dev/null @@ -1,27 +0,0 @@ -// 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. - -#include "yabloc_common/ground_server/ground_server.hpp" - -#include - -int main(int argc, char ** argv) -{ - google::InitGoogleLogging(argv[0]); - google::InstallFailureSignalHandler(); - - rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()); - rclcpp::shutdown(); -} diff --git a/localization/yabloc/yabloc_common/src/ll2_decomposer/ll2_decomposer_core.cpp b/localization/yabloc/yabloc_common/src/ll2_decomposer/ll2_decomposer_core.cpp index 5cf3e905e447d..df56f43b9287c 100644 --- a/localization/yabloc/yabloc_common/src/ll2_decomposer/ll2_decomposer_core.cpp +++ b/localization/yabloc/yabloc_common/src/ll2_decomposer/ll2_decomposer_core.cpp @@ -24,7 +24,7 @@ namespace yabloc::ll2_decomposer { -Ll2Decomposer::Ll2Decomposer() : Node("ll2_to_image") +Ll2Decomposer::Ll2Decomposer(const rclcpp::NodeOptions & options) : Node("ll2_to_image", options) { using std::placeholders::_1; const rclcpp::QoS latch_qos = rclcpp::QoS(10).transient_local(); @@ -263,3 +263,6 @@ void Ll2Decomposer::publish_additional_marker(const lanelet::LaneletMapPtr & lan } } // namespace yabloc::ll2_decomposer + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(yabloc::ll2_decomposer::Ll2Decomposer) diff --git a/localization/yabloc/yabloc_particle_filter/package.xml b/localization/yabloc/yabloc_particle_filter/package.xml index 5db4aa0c29e88..66c0d8af8865c 100644 --- a/localization/yabloc/yabloc_particle_filter/package.xml +++ b/localization/yabloc/yabloc_particle_filter/package.xml @@ -18,6 +18,7 @@ rosidl_default_generators geometry_msgs + glog rclcpp sensor_msgs sophus 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/localization/yabloc/yabloc_pose_initializer/src/camera/projector_module.cpp b/localization/yabloc/yabloc_pose_initializer/src/camera/projector_module.cpp index 86a403f68a957..baa199d5548a1 100644 --- a/localization/yabloc/yabloc_pose_initializer/src/camera/projector_module.cpp +++ b/localization/yabloc/yabloc_pose_initializer/src/camera/projector_module.cpp @@ -50,9 +50,9 @@ cv::Mat ProjectorModule::project_image(const cv::Mat & mask_image) cv::findContours(masks[i], contours, cv::RETR_LIST, cv::CHAIN_APPROX_NONE); std::vector > projected_contours; - for (auto contour : contours) { + for (const auto & contour : contours) { std::vector projected; - for (auto c : contour) { + for (const auto & c : contour) { auto opt = project_func_(c); if (!opt.has_value()) continue; diff --git a/map/map_height_fitter/CMakeLists.txt b/map/map_height_fitter/CMakeLists.txt index 8821158c54757..0dec2f6a1663a 100644 --- a/map/map_height_fitter/CMakeLists.txt +++ b/map/map_height_fitter/CMakeLists.txt @@ -5,8 +5,9 @@ find_package(autoware_cmake REQUIRED) find_package(PCL REQUIRED COMPONENTS common) autoware_package() -ament_auto_add_library(map_height_fitter SHARED +ament_auto_add_library(${PROJECT_NAME} SHARED src/map_height_fitter.cpp + src/map_height_fitter_node.cpp ) target_link_libraries(map_height_fitter ${PCL_LIBRARIES}) @@ -14,11 +15,14 @@ target_link_libraries(map_height_fitter ${PCL_LIBRARIES}) # These are treated as errors in compile, so pedantic warnings are disabled for this package. target_compile_options(map_height_fitter PRIVATE -Wno-pedantic) -ament_auto_add_executable(node - src/node.cpp +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "MapHeightFitterNode" + EXECUTABLE ${PROJECT_NAME}_node + EXECUTOR MultiThreadedExecutor ) ament_auto_package( INSTALL_TO_SHARE launch - config) + config +) diff --git a/map/map_height_fitter/launch/map_height_fitter.launch.xml b/map/map_height_fitter/launch/map_height_fitter.launch.xml index 353f2151ee172..3e01a35a8e519 100644 --- a/map/map_height_fitter/launch/map_height_fitter.launch.xml +++ b/map/map_height_fitter/launch/map_height_fitter.launch.xml @@ -3,7 +3,7 @@ - + diff --git a/map/map_height_fitter/package.xml b/map/map_height_fitter/package.xml index 7f384aa43ec7b..568c77f2509c6 100644 --- a/map/map_height_fitter/package.xml +++ b/map/map_height_fitter/package.xml @@ -25,6 +25,7 @@ libpcl-common pcl_conversions rclcpp + rclcpp_components sensor_msgs tf2_geometry_msgs tf2_ros 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; diff --git a/map/map_height_fitter/src/node.cpp b/map/map_height_fitter/src/map_height_fitter_node.cpp similarity index 83% rename from map/map_height_fitter/src/node.cpp rename to map/map_height_fitter/src/map_height_fitter_node.cpp index 55702dc08450d..fdc7604b68855 100644 --- a/map/map_height_fitter/src/node.cpp +++ b/map/map_height_fitter/src/map_height_fitter_node.cpp @@ -23,7 +23,8 @@ using tier4_localization_msgs::srv::PoseWithCovarianceStamped; class MapHeightFitterNode : public rclcpp::Node { public: - MapHeightFitterNode() : Node("map_height_fitter"), fitter_(this) + explicit MapHeightFitterNode(const rclcpp::NodeOptions & options) + : rclcpp::Node("map_height_fitter", options), fitter_(this) { const auto on_service = [this]( const PoseWithCovarianceStamped::Request::SharedPtr req, @@ -46,13 +47,5 @@ class MapHeightFitterNode : public rclcpp::Node rclcpp::Service::SharedPtr srv_; }; -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(MapHeightFitterNode) diff --git a/map/map_projection_loader/CMakeLists.txt b/map/map_projection_loader/CMakeLists.txt index f6102a1efa795..87f519ab22572 100644 --- a/map/map_projection_loader/CMakeLists.txt +++ b/map/map_projection_loader/CMakeLists.txt @@ -6,25 +6,24 @@ autoware_package() ament_auto_find_build_dependencies() -ament_auto_add_library(map_projection_loader_lib SHARED +ament_auto_add_library(${PROJECT_NAME} SHARED src/map_projection_loader.cpp src/load_info_from_lanelet2_map.cpp ) -target_link_libraries(map_projection_loader_lib yaml-cpp) - -ament_auto_add_executable(map_projection_loader src/map_projection_loader_node.cpp) - -target_compile_options(map_projection_loader PUBLIC -g -Wall -Wextra -Wpedantic -Werror) +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "MapProjectionLoader" + EXECUTABLE ${PROJECT_NAME}_node + EXECUTOR SingleThreadedExecutor +) -target_link_libraries(map_projection_loader map_projection_loader_lib) -target_include_directories(map_projection_loader PUBLIC include) +target_link_libraries(${PROJECT_NAME} yaml-cpp) function(add_testcase filepath) get_filename_component(filename ${filepath} NAME) string(REGEX REPLACE ".cpp" "" test_name ${filename}) ament_add_gmock(${test_name} ${filepath}) - target_link_libraries("${test_name}" map_projection_loader_lib) + target_link_libraries("${test_name}" ${PROJECT_NAME}) ament_target_dependencies(${test_name} ${${PROJECT_NAME}_FOUND_BUILD_DEPENDS}) endfunction() @@ -57,7 +56,8 @@ if(BUILD_TESTING) add_testcase(test/test_load_info_from_lanelet2_map.cpp) endif() -ament_auto_package(INSTALL_TO_SHARE +ament_auto_package( + INSTALL_TO_SHARE launch config ) diff --git a/map/map_projection_loader/README.md b/map/map_projection_loader/README.md index 848fcfba95f14..aa620256d977b 100644 --- a/map/map_projection_loader/README.md +++ b/map/map_projection_loader/README.md @@ -21,6 +21,10 @@ sample-map-rosbag └── pointcloud_map_metadata.yaml ``` +There are three types of transformations from latitude and longitude to XYZ coordinate system as shown in the figure below. Please refer to the following details for the necessary parameters for each projector type. + +![node_diagram](docs/map_projector_type.svg) + ### Using local coordinate ```yaml diff --git a/map/map_projection_loader/docs/map_projector_type.svg b/map/map_projection_loader/docs/map_projector_type.svg new file mode 100644 index 0000000000000..e1c8c2ac68987 --- /dev/null +++ b/map/map_projection_loader/docs/map_projector_type.svg @@ -0,0 +1,3010 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + MGRS + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + MGRS + + + X(east) + + + O + + + Y(north) + + + + Strict Boundary. + + Outside of the mgrs grid is + projected to undefined xy + + + mgrs_grid=54SUE + + + 54SUE + + + 54S(UTM grid) + + + meridian + + + LocalCartesianUTM + + + TransverseMercator + + + + + map_origin.latitude=35.6 + map_origin.longitude=139.5 + + + 3+6*floor(map_origin.longitude/6)[deg] + + + 3+6n[deg] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + X(east) + + + O + + + Y(north) + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + map_origin.latitude=35.6 + map_origin.longitude=139.5 + + + map_origin.longitude[deg] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + X(east) + + + O + + + Y(north) + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + No boundary, + but farther away from the meridian, + the greater the projection error becomes + + + + No boundary, + but farther away from the meridian, + the greater the projection error becomes + + + diff --git a/map/map_projection_loader/include/map_projection_loader/map_projection_loader.hpp b/map/map_projection_loader/include/map_projection_loader/map_projection_loader.hpp index 54e794e2742bf..05bc6e64e1675 100644 --- a/map/map_projection_loader/include/map_projection_loader/map_projection_loader.hpp +++ b/map/map_projection_loader/include/map_projection_loader/map_projection_loader.hpp @@ -29,7 +29,7 @@ tier4_map_msgs::msg::MapProjectorInfo load_map_projector_info( class MapProjectionLoader : public rclcpp::Node { public: - MapProjectionLoader(); + explicit MapProjectionLoader(const rclcpp::NodeOptions & options); private: using MapProjectorInfo = map_interface::MapProjectorInfo; diff --git a/map/map_projection_loader/launch/map_projection_loader.launch.xml b/map/map_projection_loader/launch/map_projection_loader.launch.xml index a6570b69d3498..13418a7e97423 100644 --- a/map/map_projection_loader/launch/map_projection_loader.launch.xml +++ b/map/map_projection_loader/launch/map_projection_loader.launch.xml @@ -4,7 +4,7 @@ - + diff --git a/map/map_projection_loader/package.xml b/map/map_projection_loader/package.xml index 475881577bd58..7a930085cd7b1 100644 --- a/map/map_projection_loader/package.xml +++ b/map/map_projection_loader/package.xml @@ -21,6 +21,7 @@ component_interface_utils lanelet2_extension rclcpp + rclcpp_components tier4_map_msgs yaml-cpp diff --git a/map/map_projection_loader/src/map_projection_loader.cpp b/map/map_projection_loader/src/map_projection_loader.cpp index 5966baaed8383..383051e8f67a5 100644 --- a/map/map_projection_loader/src/map_projection_loader.cpp +++ b/map/map_projection_loader/src/map_projection_loader.cpp @@ -82,7 +82,8 @@ tier4_map_msgs::msg::MapProjectorInfo load_map_projector_info( return msg; } -MapProjectionLoader::MapProjectionLoader() : Node("map_projection_loader") +MapProjectionLoader::MapProjectionLoader(const rclcpp::NodeOptions & options) +: rclcpp::Node("map_projection_loader", options) { const std::string yaml_filename = this->declare_parameter("map_projector_info_path"); const std::string lanelet2_map_filename = @@ -96,3 +97,6 @@ MapProjectionLoader::MapProjectionLoader() : Node("map_projection_loader") adaptor.init_pub(publisher_); publisher_->publish(msg); } + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(MapProjectionLoader) 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 b8540550ce9da..0d0b5cb31afba 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 @@ -44,7 +44,7 @@ def generate_test_description(): map_projection_loader_node = Node( package="map_projection_loader", - executable="map_projection_loader", + executable="map_projection_loader_node", output="screen", parameters=[ { 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 c7697038cc253..6a17ff340b19f 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 @@ -44,7 +44,7 @@ def generate_test_description(): map_projection_loader_node = Node( package="map_projection_loader", - executable="map_projection_loader", + executable="map_projection_loader_node", output="screen", parameters=[ { 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 f75beddc6827c..37cfd9936bf20 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 @@ -44,7 +44,7 @@ def generate_test_description(): map_projection_loader_node = Node( package="map_projection_loader", - executable="map_projection_loader", + executable="map_projection_loader_node", output="screen", parameters=[ { 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 765f3cde04679..7bccdc7875454 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 @@ -44,7 +44,7 @@ def generate_test_description(): map_projection_loader_node = Node( package="map_projection_loader", - executable="map_projection_loader", + executable="map_projection_loader_node", output="screen", parameters=[ { diff --git a/map/map_tf_generator/launch/map_tf_generator.launch.xml b/map/map_tf_generator/launch/map_tf_generator.launch.xml index 43d487c2bc982..197085f31d9c4 100644 --- a/map/map_tf_generator/launch/map_tf_generator.launch.xml +++ b/map/map_tf_generator/launch/map_tf_generator.launch.xml @@ -3,7 +3,7 @@ - + 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; diff --git a/perception/detected_object_validation/CMakeLists.txt b/perception/detected_object_validation/CMakeLists.txt index f882c6dd165fe..d023c6c9df328 100644 --- a/perception/detected_object_validation/CMakeLists.txt +++ b/perception/detected_object_validation/CMakeLists.txt @@ -85,6 +85,12 @@ rclcpp_components_register_node(occupancy_grid_based_validator EXECUTABLE occupancy_grid_based_validator_node ) +if(BUILD_TESTING) + ament_auto_add_gtest(detection_object_validation_tests + test/test_utils.cpp + ) +endif() + ament_auto_package(INSTALL_TO_SHARE launch config diff --git a/perception/detected_object_validation/config/object_lanelet_filter.param.yaml b/perception/detected_object_validation/config/object_lanelet_filter.param.yaml index dfdee95642fed..99050d9738ae6 100644 --- a/perception/detected_object_validation/config/object_lanelet_filter.param.yaml +++ b/perception/detected_object_validation/config/object_lanelet_filter.param.yaml @@ -9,3 +9,13 @@ MOTORCYCLE : false BICYCLE : false PEDESTRIAN : false + + filter_settings: + # polygon overlap based filter + polygon_overlap_filter: + enabled: true + # velocity direction based filter + lanelet_direction_filter: + enabled: false + velocity_yaw_threshold: 0.785398 # [rad] (45 deg) + object_speed_threshold: 3.0 # [m/s] diff --git a/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp b/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp index f3871aaf98117..6c652d0ad093e 100644 --- a/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp +++ b/perception/detected_object_validation/include/detected_object_validation/detected_object_filter/object_lanelet_filter.hpp @@ -17,6 +17,7 @@ #include "detected_object_validation/utils/utils.hpp" +#include #include #include #include @@ -62,11 +63,30 @@ class ObjectLaneletFilterNode : public rclcpp::Node tf2_ros::TransformListener tf_listener_; utils::FilterTargetLabel filter_target_; - + struct FilterSettings + { + bool polygon_overlap_filter; + bool lanelet_direction_filter; + double lanelet_direction_filter_velocity_yaw_threshold; + double lanelet_direction_filter_object_speed_threshold; + } filter_settings_; + + bool filterObject( + const autoware_auto_perception_msgs::msg::DetectedObject & transformed_object, + const autoware_auto_perception_msgs::msg::DetectedObject & input_object, + const lanelet::ConstLanelets & intersected_road_lanelets, + const lanelet::ConstLanelets & intersected_shoulder_lanelets, + autoware_auto_perception_msgs::msg::DetectedObjects & output_object_msg); LinearRing2d getConvexHull(const autoware_auto_perception_msgs::msg::DetectedObjects &); lanelet::ConstLanelets getIntersectedLanelets( const LinearRing2d &, const lanelet::ConstLanelets &); + bool isObjectOverlapLanelets( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const lanelet::ConstLanelets & intersected_lanelets); bool isPolygonOverlapLanelets(const Polygon2d &, const lanelet::ConstLanelets &); + bool isSameDirectionWithLanelets( + const lanelet::ConstLanelets & lanelets, + const autoware_auto_perception_msgs::msg::DetectedObject & object); geometry_msgs::msg::Polygon setFootprint( const autoware_auto_perception_msgs::msg::DetectedObject &); diff --git a/perception/detected_object_validation/include/detected_object_validation/utils/utils.hpp b/perception/detected_object_validation/include/detected_object_validation/utils/utils.hpp index 2c46e1b9dd110..853733dc0ee5f 100644 --- a/perception/detected_object_validation/include/detected_object_validation/utils/utils.hpp +++ b/perception/detected_object_validation/include/detected_object_validation/utils/utils.hpp @@ -15,8 +15,9 @@ #ifndef DETECTED_OBJECT_VALIDATION__UTILS__UTILS_HPP_ #define DETECTED_OBJECT_VALIDATION__UTILS__UTILS_HPP_ -#include +#include +#include namespace utils { struct FilterTargetLabel @@ -31,6 +32,21 @@ struct FilterTargetLabel bool PEDESTRIAN; bool isTarget(const uint8_t label) const; }; // struct FilterTargetLabel + +inline bool hasBoundingBox(const autoware_auto_perception_msgs::msg::DetectedObject & object) +{ + if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { + return true; + } else if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::CYLINDER) { + return true; + } else if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::POLYGON) { + return false; + } else { + // unknown shape type. + return false; + } +} + } // namespace utils #endif // DETECTED_OBJECT_VALIDATION__UTILS__UTILS_HPP_ diff --git a/perception/detected_object_validation/src/object_lanelet_filter.cpp b/perception/detected_object_validation/src/object_lanelet_filter.cpp index 50a81e95d5a9b..80a2ce4b6563f 100644 --- a/perception/detected_object_validation/src/object_lanelet_filter.cpp +++ b/perception/detected_object_validation/src/object_lanelet_filter.cpp @@ -43,6 +43,15 @@ ObjectLaneletFilterNode::ObjectLaneletFilterNode(const rclcpp::NodeOptions & nod filter_target_.MOTORCYCLE = declare_parameter("filter_target_label.MOTORCYCLE", false); filter_target_.BICYCLE = declare_parameter("filter_target_label.BICYCLE", false); filter_target_.PEDESTRIAN = declare_parameter("filter_target_label.PEDESTRIAN", false); + // Set filter settings + filter_settings_.polygon_overlap_filter = + declare_parameter("filter_settings.polygon_overlap_filter.enabled"); + filter_settings_.lanelet_direction_filter = + declare_parameter("filter_settings.lanelet_direction_filter.enabled"); + filter_settings_.lanelet_direction_filter_velocity_yaw_threshold = + declare_parameter("filter_settings.lanelet_direction_filter.velocity_yaw_threshold"); + filter_settings_.lanelet_direction_filter_object_speed_threshold = + declare_parameter("filter_settings.lanelet_direction_filter.object_speed_threshold"); // Set publisher/subscriber map_sub_ = this->create_subscription( @@ -97,27 +106,13 @@ void ObjectLaneletFilterNode::objectCallback( lanelet::ConstLanelets intersected_shoulder_lanelets = getIntersectedLanelets(convex_hull, shoulder_lanelets_); - int index = 0; - for (const auto & object : transformed_objects.objects) { - const auto footprint = setFootprint(object); - const auto & label = object.classification.front().label; - if (filter_target_.isTarget(label)) { - Polygon2d polygon; - for (const auto & point : footprint.points) { - const geometry_msgs::msg::Point32 point_transformed = - tier4_autoware_utils::transformPoint(point, object.kinematics.pose_with_covariance.pose); - polygon.outer().emplace_back(point_transformed.x, point_transformed.y); - } - polygon.outer().push_back(polygon.outer().front()); - if (isPolygonOverlapLanelets(polygon, intersected_road_lanelets)) { - output_object_msg.objects.emplace_back(input_msg->objects.at(index)); - } else if (isPolygonOverlapLanelets(polygon, intersected_shoulder_lanelets)) { - output_object_msg.objects.emplace_back(input_msg->objects.at(index)); - } - } else { - output_object_msg.objects.emplace_back(input_msg->objects.at(index)); - } - ++index; + // filtering process + for (size_t index = 0; index < transformed_objects.objects.size(); ++index) { + const auto & transformed_object = transformed_objects.objects.at(index); + const auto & input_object = input_msg->objects.at(index); + filterObject( + transformed_object, input_object, intersected_road_lanelets, intersected_shoulder_lanelets, + output_object_msg); } object_pub_->publish(output_object_msg); published_time_publisher_->publish_if_subscribed(object_pub_, output_object_msg.header.stamp); @@ -132,6 +127,47 @@ void ObjectLaneletFilterNode::objectCallback( "debug/pipeline_latency_ms", pipeline_latency); } +bool ObjectLaneletFilterNode::filterObject( + const autoware_auto_perception_msgs::msg::DetectedObject & transformed_object, + const autoware_auto_perception_msgs::msg::DetectedObject & input_object, + const lanelet::ConstLanelets & intersected_road_lanelets, + const lanelet::ConstLanelets & intersected_shoulder_lanelets, + autoware_auto_perception_msgs::msg::DetectedObjects & output_object_msg) +{ + const auto & label = transformed_object.classification.front().label; + if (filter_target_.isTarget(label)) { + bool filter_pass = true; + // 1. is polygon overlap with road lanelets or shoulder lanelets + if (filter_settings_.polygon_overlap_filter) { + const bool is_polygon_overlap = + isObjectOverlapLanelets(transformed_object, intersected_road_lanelets) || + isObjectOverlapLanelets(transformed_object, intersected_shoulder_lanelets); + filter_pass = filter_pass && is_polygon_overlap; + } + + // 2. check if objects velocity is the same with the lanelet direction + const bool orientation_not_available = + transformed_object.kinematics.orientation_availability == + autoware_auto_perception_msgs::msg::TrackedObjectKinematics::UNAVAILABLE; + if (filter_settings_.lanelet_direction_filter && !orientation_not_available) { + const bool is_same_direction = + isSameDirectionWithLanelets(intersected_road_lanelets, transformed_object) || + isSameDirectionWithLanelets(intersected_shoulder_lanelets, transformed_object); + filter_pass = filter_pass && is_same_direction; + } + + // push back to output object + if (filter_pass) { + output_object_msg.objects.emplace_back(input_object); + return true; + } + } else { + output_object_msg.objects.emplace_back(input_object); + return true; + } + return false; +} + geometry_msgs::msg::Polygon ObjectLaneletFilterNode::setFootprint( const autoware_auto_perception_msgs::msg::DetectedObject & detected_object) { @@ -190,6 +226,39 @@ lanelet::ConstLanelets ObjectLaneletFilterNode::getIntersectedLanelets( return intersected_lanelets; } +bool ObjectLaneletFilterNode::isObjectOverlapLanelets( + const autoware_auto_perception_msgs::msg::DetectedObject & object, + const lanelet::ConstLanelets & intersected_lanelets) +{ + // if has bounding box, use polygon overlap + if (utils::hasBoundingBox(object)) { + Polygon2d polygon; + const auto footprint = setFootprint(object); + for (const auto & point : footprint.points) { + const geometry_msgs::msg::Point32 point_transformed = + tier4_autoware_utils::transformPoint(point, object.kinematics.pose_with_covariance.pose); + polygon.outer().emplace_back(point_transformed.x, point_transformed.y); + } + polygon.outer().push_back(polygon.outer().front()); + return isPolygonOverlapLanelets(polygon, intersected_lanelets); + } else { + // if object do not have bounding box, check each footprint is inside polygon + for (const auto & point : object.shape.footprint.points) { + const geometry_msgs::msg::Point32 point_transformed = + tier4_autoware_utils::transformPoint(point, object.kinematics.pose_with_covariance.pose); + geometry_msgs::msg::Pose point2d; + point2d.position.x = point_transformed.x; + point2d.position.y = point_transformed.y; + for (const auto & lanelet : intersected_lanelets) { + if (lanelet::utils::isInLanelet(point2d, lanelet, 0.0)) { + return true; + } + } + } + return false; + } +} + bool ObjectLaneletFilterNode::isPolygonOverlapLanelets( const Polygon2d & polygon, const lanelet::ConstLanelets & intersected_lanelets) { @@ -201,6 +270,42 @@ bool ObjectLaneletFilterNode::isPolygonOverlapLanelets( return false; } +bool ObjectLaneletFilterNode::isSameDirectionWithLanelets( + const lanelet::ConstLanelets & lanelets, + const autoware_auto_perception_msgs::msg::DetectedObject & object) +{ + const double object_yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); + const double object_velocity_norm = std::hypot( + object.kinematics.twist_with_covariance.twist.linear.x, + object.kinematics.twist_with_covariance.twist.linear.y); + const double object_velocity_yaw = std::atan2( + object.kinematics.twist_with_covariance.twist.linear.y, + object.kinematics.twist_with_covariance.twist.linear.x) + + object_yaw; + + if (object_velocity_norm < filter_settings_.lanelet_direction_filter_object_speed_threshold) { + return true; + } + for (const auto & lanelet : lanelets) { + const bool is_in_lanelet = + lanelet::utils::isInLanelet(object.kinematics.pose_with_covariance.pose, lanelet, 0.0); + if (!is_in_lanelet) { + continue; + } + const double lane_yaw = lanelet::utils::getLaneletAngle( + lanelet, object.kinematics.pose_with_covariance.pose.position); + const double delta_yaw = object_velocity_yaw - lane_yaw; + const double normalized_delta_yaw = tier4_autoware_utils::normalizeRadian(delta_yaw); + const double abs_norm_delta_yaw = std::fabs(normalized_delta_yaw); + + if (abs_norm_delta_yaw < filter_settings_.lanelet_direction_filter_velocity_yaw_threshold) { + return true; + } + } + + return false; +} + } // namespace object_lanelet_filter #include diff --git a/perception/detected_object_validation/test/test_utils.cpp b/perception/detected_object_validation/test/test_utils.cpp new file mode 100644 index 0000000000000..ace4dd10a191f --- /dev/null +++ b/perception/detected_object_validation/test/test_utils.cpp @@ -0,0 +1,67 @@ +// 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 "detected_object_validation/utils/utils.hpp" + +#include + +#include + +using AutowareLabel = autoware_auto_perception_msgs::msg::ObjectClassification; + +utils::FilterTargetLabel createFilterTargetAll() +{ + utils::FilterTargetLabel filter; + filter.UNKNOWN = true; + filter.CAR = true; + filter.TRUCK = true; + filter.BUS = true; + filter.TRAILER = true; + filter.MOTORCYCLE = true; + filter.BICYCLE = true; + filter.PEDESTRIAN = true; + return filter; +} + +utils::FilterTargetLabel createFilterTargetVehicle() +{ + utils::FilterTargetLabel filter; + filter.UNKNOWN = false; + filter.CAR = true; + filter.TRUCK = true; + filter.BUS = true; + filter.TRAILER = true; + filter.MOTORCYCLE = false; + filter.BICYCLE = false; + filter.PEDESTRIAN = false; + return filter; +} + +TEST(IsTargetTest, AllTarget) +{ + auto filter = createFilterTargetAll(); + auto label = AutowareLabel::CAR; + EXPECT_TRUE(filter.isTarget(label)); +} + +TEST(IsTargetTest, VehicleTarget) +{ + auto filter = createFilterTargetVehicle(); + + auto car_label = AutowareLabel::CAR; + EXPECT_TRUE(filter.isTarget(car_label)); + + auto unknown_label = AutowareLabel::UNKNOWN; + EXPECT_FALSE(filter.isTarget(unknown_label)); +} diff --git a/perception/euclidean_cluster/include/euclidean_cluster/euclidean_cluster.hpp b/perception/euclidean_cluster/include/euclidean_cluster/euclidean_cluster.hpp index f1e275a919a8a..aec3f56936828 100644 --- a/perception/euclidean_cluster/include/euclidean_cluster/euclidean_cluster.hpp +++ b/perception/euclidean_cluster/include/euclidean_cluster/euclidean_cluster.hpp @@ -32,6 +32,10 @@ class EuclideanCluster : public EuclideanClusterInterface bool cluster( const pcl::PointCloud::ConstPtr & pointcloud, std::vector> & clusters) override; + + bool cluster( + const sensor_msgs::msg::PointCloud2::ConstSharedPtr & pointcloud, + tier4_perception_msgs::msg::DetectedObjectsWithFeature & clusters) override; void setTolerance(float tolerance) { tolerance_ = tolerance; } private: diff --git a/perception/euclidean_cluster/include/euclidean_cluster/euclidean_cluster_interface.hpp b/perception/euclidean_cluster/include/euclidean_cluster/euclidean_cluster_interface.hpp index 70c21daabcd66..65b907f747666 100644 --- a/perception/euclidean_cluster/include/euclidean_cluster/euclidean_cluster_interface.hpp +++ b/perception/euclidean_cluster/include/euclidean_cluster/euclidean_cluster_interface.hpp @@ -16,6 +16,9 @@ #include +#include +#include + #include #include @@ -41,6 +44,10 @@ class EuclideanClusterInterface const pcl::PointCloud::ConstPtr & pointcloud, std::vector> & clusters) = 0; + virtual bool cluster( + const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_msg, + tier4_perception_msgs::msg::DetectedObjectsWithFeature & output_clusters) = 0; + protected: bool use_height_ = true; int min_cluster_size_; diff --git a/perception/euclidean_cluster/include/euclidean_cluster/utils.hpp b/perception/euclidean_cluster/include/euclidean_cluster/utils.hpp index 2ac77aebdea0c..50d2306d48f72 100644 --- a/perception/euclidean_cluster/include/euclidean_cluster/utils.hpp +++ b/perception/euclidean_cluster/include/euclidean_cluster/utils.hpp @@ -31,6 +31,9 @@ void convertPointCloudClusters2Msg( const std_msgs::msg::Header & header, const std::vector> & clusters, tier4_perception_msgs::msg::DetectedObjectsWithFeature & msg); +void convertPointCloudClusters2Msg( + const std_msgs::msg::Header & header, const std::vector & clusters, + tier4_perception_msgs::msg::DetectedObjectsWithFeature & msg); void convertObjectMsg2SensorMsg( const tier4_perception_msgs::msg::DetectedObjectsWithFeature & input, sensor_msgs::msg::PointCloud2 & output); diff --git a/perception/euclidean_cluster/include/euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp b/perception/euclidean_cluster/include/euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp index d6a07503c5ca5..375cc2d19a01f 100644 --- a/perception/euclidean_cluster/include/euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp +++ b/perception/euclidean_cluster/include/euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp @@ -35,6 +35,9 @@ class VoxelGridBasedEuclideanCluster : public EuclideanClusterInterface bool cluster( const pcl::PointCloud::ConstPtr & pointcloud, std::vector> & clusters) override; + bool cluster( + const sensor_msgs::msg::PointCloud2::ConstSharedPtr & pointcloud, + tier4_perception_msgs::msg::DetectedObjectsWithFeature & clusters) override; void setVoxelLeafSize(float voxel_leaf_size) { voxel_leaf_size_ = voxel_leaf_size; } void setTolerance(float tolerance) { tolerance_ = tolerance; } void setMinPointsNumberPerVoxel(int min_points_number_per_voxel) diff --git a/perception/euclidean_cluster/lib/euclidean_cluster.cpp b/perception/euclidean_cluster/lib/euclidean_cluster.cpp index bd8270bd6b881..5ba1b99403280 100644 --- a/perception/euclidean_cluster/lib/euclidean_cluster.cpp +++ b/perception/euclidean_cluster/lib/euclidean_cluster.cpp @@ -33,6 +33,15 @@ EuclideanCluster::EuclideanCluster( : EuclideanClusterInterface(use_height, min_cluster_size, max_cluster_size), tolerance_(tolerance) { } +// TODO(badai-nguyen): implement input field copy for euclidean_cluster.cpp +bool EuclideanCluster::cluster( + const sensor_msgs::msg::PointCloud2::ConstSharedPtr & pointcloud_msg, + tier4_perception_msgs::msg::DetectedObjectsWithFeature & clusters) +{ + (void)pointcloud_msg; + (void)clusters; + return false; +} bool EuclideanCluster::cluster( const pcl::PointCloud::ConstPtr & pointcloud, diff --git a/perception/euclidean_cluster/lib/utils.cpp b/perception/euclidean_cluster/lib/utils.cpp index 6ff563c157d00..3a906575e2c1e 100644 --- a/perception/euclidean_cluster/lib/utils.cpp +++ b/perception/euclidean_cluster/lib/utils.cpp @@ -62,6 +62,25 @@ void convertPointCloudClusters2Msg( msg.feature_objects.push_back(feature_object); } } + +void convertPointCloudClusters2Msg( + const std_msgs::msg::Header & header, const std::vector & clusters, + tier4_perception_msgs::msg::DetectedObjectsWithFeature & msg) +{ + msg.header = header; + for (const auto & ros_pointcloud : clusters) { + tier4_perception_msgs::msg::DetectedObjectWithFeature feature_object; + feature_object.feature.cluster = ros_pointcloud; + feature_object.object.kinematics.pose_with_covariance.pose.position = + getCentroid(ros_pointcloud); + autoware_auto_perception_msgs::msg::ObjectClassification classification; + classification.label = autoware_auto_perception_msgs::msg::ObjectClassification::UNKNOWN; + classification.probability = 1.0f; + feature_object.object.classification.emplace_back(classification); + msg.feature_objects.push_back(feature_object); + } +} + void convertObjectMsg2SensorMsg( const tier4_perception_msgs::msg::DetectedObjectsWithFeature & input, sensor_msgs::msg::PointCloud2 & output) diff --git a/perception/euclidean_cluster/lib/voxel_grid_based_euclidean_cluster.cpp b/perception/euclidean_cluster/lib/voxel_grid_based_euclidean_cluster.cpp index b8276296dde5f..d82ec021a5396 100644 --- a/perception/euclidean_cluster/lib/voxel_grid_based_euclidean_cluster.cpp +++ b/perception/euclidean_cluster/lib/voxel_grid_based_euclidean_cluster.cpp @@ -40,14 +40,27 @@ VoxelGridBasedEuclideanCluster::VoxelGridBasedEuclideanCluster( min_points_number_per_voxel_(min_points_number_per_voxel) { } - +// TODO(badai-nguyen): remove this function when field copying also implemented for +// euclidean_cluster.cpp bool VoxelGridBasedEuclideanCluster::cluster( const pcl::PointCloud::ConstPtr & pointcloud, std::vector> & clusters) +{ + (void)pointcloud; + (void)clusters; + return false; +} + +bool VoxelGridBasedEuclideanCluster::cluster( + const sensor_msgs::msg::PointCloud2::ConstSharedPtr & pointcloud_msg, + tier4_perception_msgs::msg::DetectedObjectsWithFeature & objects) { // TODO(Saito) implement use_height is false version // create voxel + pcl::PointCloud::Ptr pointcloud(new pcl::PointCloud); + int point_step = pointcloud_msg->point_step; + pcl::fromROSMsg(*pointcloud_msg, *pointcloud); pcl::PointCloud::Ptr voxel_map_ptr(new pcl::PointCloud); voxel_grid_.setLeafSize(voxel_leaf_size_, voxel_leaf_size_, 100000.0); voxel_grid_.setMinimumPointsNumberPerVoxel(min_points_number_per_voxel_); @@ -81,36 +94,69 @@ bool VoxelGridBasedEuclideanCluster::cluster( // create map to search cluster index from voxel grid index std::unordered_map map; + std::vector temporary_clusters; // no check about cluster size + std::vector clusters_data_size; + temporary_clusters.resize(cluster_indices.size()); for (size_t cluster_idx = 0; cluster_idx < cluster_indices.size(); ++cluster_idx) { const auto & cluster = cluster_indices.at(cluster_idx); + auto & temporary_cluster = temporary_clusters.at(cluster_idx); for (const auto & point_idx : cluster.indices) { map[point_idx] = cluster_idx; } + temporary_cluster.height = pointcloud_msg->height; + temporary_cluster.fields = pointcloud_msg->fields; + temporary_cluster.point_step = point_step; + temporary_cluster.data.resize(max_cluster_size_ * point_step); + clusters_data_size.push_back(0); } // create vector of point cloud cluster. vector index is voxel grid index. - std::vector> temporary_clusters; // no check about cluster size - temporary_clusters.resize(cluster_indices.size()); - for (const auto & point : pointcloud->points) { + for (size_t i = 0; i < pointcloud->points.size(); ++i) { + const auto & point = pointcloud->points.at(i); const int index = voxel_grid_.getCentroidIndexAt(voxel_grid_.getGridCoordinates(point.x, point.y, point.z)); if (map.find(index) != map.end()) { - temporary_clusters.at(map[index]).points.push_back(point); + auto & cluster_data_size = clusters_data_size.at(map[index]); + if (cluster_data_size + point_step > std::size_t(max_cluster_size_ * point_step)) { + continue; + } + std::memcpy( + &temporary_clusters.at(map[index]).data[cluster_data_size], + &pointcloud_msg->data[i * point_step], point_step); + cluster_data_size += point_step; } } // build output and check cluster size { - for (const auto & cluster : temporary_clusters) { - if (!(min_cluster_size_ <= static_cast(cluster.points.size()) && - static_cast(cluster.points.size()) <= max_cluster_size_)) { + for (size_t i = 0; i < temporary_clusters.size(); ++i) { + auto & i_cluster_data_size = clusters_data_size.at(i); + if (!(min_cluster_size_ <= static_cast(i_cluster_data_size / point_step) && + static_cast(i_cluster_data_size / point_step) <= max_cluster_size_)) { continue; } - clusters.push_back(cluster); - clusters.back().width = cluster.points.size(); - clusters.back().height = 1; - clusters.back().is_dense = false; + const auto & cluster = temporary_clusters.at(i); + tier4_perception_msgs::msg::DetectedObjectWithFeature feature_object; + feature_object.feature.cluster = cluster; + feature_object.feature.cluster.data.resize(i_cluster_data_size); + feature_object.feature.cluster.header = pointcloud_msg->header; + feature_object.feature.cluster.is_bigendian = pointcloud_msg->is_bigendian; + feature_object.feature.cluster.is_dense = pointcloud_msg->is_dense; + feature_object.feature.cluster.point_step = point_step; + feature_object.feature.cluster.row_step = i_cluster_data_size / pointcloud_msg->height; + feature_object.feature.cluster.width = + i_cluster_data_size / point_step / pointcloud_msg->height; + + feature_object.object.kinematics.pose_with_covariance.pose.position = + getCentroid(feature_object.feature.cluster); + autoware_auto_perception_msgs::msg::ObjectClassification classification; + classification.label = autoware_auto_perception_msgs::msg::ObjectClassification::UNKNOWN; + classification.probability = 1.0f; + feature_object.object.classification.emplace_back(classification); + + objects.feature_objects.push_back(feature_object); } + objects.header = pointcloud_msg->header; } return true; diff --git a/perception/euclidean_cluster/src/voxel_grid_based_euclidean_cluster_node.cpp b/perception/euclidean_cluster/src/voxel_grid_based_euclidean_cluster_node.cpp index f58d9ac6dcc48..7e6a456561900 100644 --- a/perception/euclidean_cluster/src/voxel_grid_based_euclidean_cluster_node.cpp +++ b/perception/euclidean_cluster/src/voxel_grid_based_euclidean_cluster_node.cpp @@ -55,24 +55,15 @@ void VoxelGridBasedEuclideanClusterNode::onPointCloud( stop_watch_ptr_->toc("processing_time", true); // convert ros to pcl - pcl::PointCloud::Ptr raw_pointcloud_ptr(new pcl::PointCloud); if (input_msg->data.empty()) { // NOTE: prevent pcl log spam RCLCPP_WARN_STREAM_THROTTLE( this->get_logger(), *this->get_clock(), 1000, "Empty sensor points!"); - } else { - pcl::fromROSMsg(*input_msg, *raw_pointcloud_ptr); } - - // clustering - std::vector> clusters; - if (!raw_pointcloud_ptr->empty()) { - cluster_->cluster(raw_pointcloud_ptr, clusters); - } - - // build output msg + // cluster and build output msg tier4_perception_msgs::msg::DetectedObjectsWithFeature output; - convertPointCloudClusters2Msg(input_msg->header, clusters, output); + + cluster_->cluster(input_msg, output); cluster_pub_->publish(output); // build debug msg 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/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/ground_segmentation/src/ransac_ground_filter_nodelet.cpp b/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp index ed5fb6abe7fe7..d7fa777dc58c9 100644 --- a/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp +++ b/perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp @@ -102,9 +102,7 @@ RANSACGroundFilterComponent::RANSACGroundFilterComponent(const rclcpp::NodeOptio unit_vec_ = Eigen::Vector3d::UnitX(); } else if (unit_axis_ == "y") { unit_vec_ = Eigen::Vector3d::UnitY(); - } else if (unit_axis_ == "z") { - unit_vec_ = Eigen::Vector3d::UnitZ(); - } else { + } else { // including (unit_axis_ == "z") unit_vec_ = Eigen::Vector3d::UnitZ(); } @@ -284,19 +282,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( @@ -367,9 +382,7 @@ rcl_interfaces::msg::SetParametersResult RANSACGroundFilterComponent::paramCallb unit_vec_ = Eigen::Vector3d::UnitX(); } else if (unit_axis_ == "y") { unit_vec_ = Eigen::Vector3d::UnitY(); - } else if (unit_axis_ == "z") { - unit_vec_ = Eigen::Vector3d::UnitZ(); - } else { + } else { // including (unit_axis_ == "z") unit_vec_ = Eigen::Vector3d::UnitZ(); } RCLCPP_DEBUG(get_logger(), "Setting unit_axis to: %s.", unit_axis_.c_str()); 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 34573b564fa36..a63d218df62de 100644 --- a/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp +++ b/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp @@ -349,13 +349,12 @@ void ScanGroundFilterComponent::classifyPointCloudGridScan( // check the first point in ray auto * p = &in_radial_ordered_clouds[i][0]; - auto * prev_p = &in_radial_ordered_clouds[i][0]; // for checking the distance to prev point bool initialized_first_gnd_grid = false; bool prev_list_init = false; pcl::PointXYZ p_orig_point, prev_p_orig_point; for (auto & point : in_radial_ordered_clouds[i]) { - prev_p = p; + auto * prev_p = p; // for checking the distance to prev point prev_p_orig_point = p_orig_point; p = &point; get_point_from_global_offset(in_cloud, p_orig_point, in_cloud->point_step * p->orig_index); @@ -388,19 +387,13 @@ void ScanGroundFilterComponent::classifyPointCloudGridScan( } // initialize lists of previous gnd grids - if (prev_list_init == false && initialized_first_gnd_grid == true) { + if (!prev_list_init) { float h = ground_cluster.getAverageHeight(); float r = ground_cluster.getAverageRadius(); initializeFirstGndGrids(h, r, p->grid_id, gnd_grids); prev_list_init = true; } - if (prev_list_init == false && initialized_first_gnd_grid == false) { - // assume first gnd grid is zero - initializeFirstGndGrids(0.0f, p->radius, p->grid_id, gnd_grids); - prev_list_init = true; - } - // move to new grid if (p->grid_id > prev_p->grid_id && ground_cluster.getAverageRadius() > 0.0) { // check if the prev grid have ground point cloud @@ -475,7 +468,6 @@ void ScanGroundFilterComponent::classifyPointCloud( float prev_gnd_slope = 0.0f; float points_distance = 0.0f; PointsCentroid ground_cluster, non_ground_cluster; - float local_slope = 0.0f; PointLabel prev_point_label = PointLabel::INIT; pcl::PointXYZ prev_gnd_point(0, 0, 0), p_orig_point, prev_p_orig_point; // loop through each point in the radial div @@ -530,7 +522,7 @@ void ScanGroundFilterComponent::classifyPointCloud( } if (calculate_slope) { // far from the previous point - local_slope = std::atan2(height_from_gnd, radius_distance_from_gnd); + auto local_slope = std::atan2(height_from_gnd, radius_distance_from_gnd); if (local_slope - prev_gnd_slope > local_slope_max_angle) { // the point is outside of the local slope threshold p->point_state = PointLabel::NON_GROUND; @@ -581,8 +573,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; } } @@ -612,7 +602,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; diff --git a/perception/image_projection_based_fusion/CMakeLists.txt b/perception/image_projection_based_fusion/CMakeLists.txt index b13f68b07181e..0f4cb7112f74a 100644 --- a/perception/image_projection_based_fusion/CMakeLists.txt +++ b/perception/image_projection_based_fusion/CMakeLists.txt @@ -160,6 +160,19 @@ else() message("Skipping build of some nodes due to missing dependencies") endif() +if(BUILD_TESTING) + find_package(ament_cmake_gtest REQUIRED) + ament_auto_add_gtest(test_calc_iou_functions + test/test_calc_iou_functions.cpp + ) + ament_auto_add_gtest(test_utils + test/test_utils.cpp + ) + ament_auto_add_gtest(test_geometry + test/test_geometry.cpp + ) +endif() + ament_auto_package(INSTALL_TO_SHARE launch config diff --git a/perception/image_projection_based_fusion/config/roi_sync.param.yaml b/perception/image_projection_based_fusion/config/fusion_common.param.yaml similarity index 100% rename from perception/image_projection_based_fusion/config/roi_sync.param.yaml rename to perception/image_projection_based_fusion/config/fusion_common.param.yaml diff --git a/perception/image_projection_based_fusion/config/pointpainting.param.yaml b/perception/image_projection_based_fusion/config/pointpainting.param.yaml old mode 100755 new mode 100644 index 53ac6f4cafc28..30136bc8f47d0 --- a/perception/image_projection_based_fusion/config/pointpainting.param.yaml +++ b/perception/image_projection_based_fusion/config/pointpainting.param.yaml @@ -1,26 +1,10 @@ /**: ros__parameters: - trt_precision: fp16 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" - - model_params: - class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] - paint_class_names: ["CAR", "BICYCLE", "PEDESTRIAN"] - point_feature_size: 7 # x, y, z, time-lag and car, pedestrian, bicycle - max_voxel_size: 40000 - point_cloud_range: [-121.6, -76.8, -3.0, 121.6, 76.8, 5.0] - voxel_size: [0.32, 0.32, 8.0] - 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" - num_past_frames: 0 + trt_precision: fp16 post_process_params: # post-process params circle_nms_dist_threshold: 0.3 @@ -28,6 +12,10 @@ iou_nms_search_distance_2d: 10.0 iou_nms_threshold: 0.1 score_threshold: 0.35 + yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] + densification_params: + world_frame_id: "map" + num_past_frames: 1 omp_params: # omp params num_threads: 1 diff --git a/perception/image_projection_based_fusion/config/pointpainting_ml_package.param.yaml b/perception/image_projection_based_fusion/config/pointpainting_ml_package.param.yaml new file mode 100755 index 0000000000000..ca76a8ecf2dac --- /dev/null +++ b/perception/image_projection_based_fusion/config/pointpainting_ml_package.param.yaml @@ -0,0 +1,13 @@ +/**: + ros__parameters: + model_params: + class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] + paint_class_names: ["CAR", "BICYCLE", "PEDESTRIAN"] + point_feature_size: 7 # x, y, z, time-lag and car, pedestrian, bicycle + max_voxel_size: 40000 + point_cloud_range: [-121.6, -76.8, -3.0, 121.6, 76.8, 5.0] + voxel_size: [0.32, 0.32, 8.0] + downsample_factor: 1 + encoder_in_feature_size: 12 + has_twist: false + has_variance: false diff --git a/perception/image_projection_based_fusion/config/segmentation_pointcloud_fusion.param.yaml b/perception/image_projection_based_fusion/config/segmentation_pointcloud_fusion.param.yaml index 79a8b860ebdd3..2120a909cd672 100644 --- a/perception/image_projection_based_fusion/config/segmentation_pointcloud_fusion.param.yaml +++ b/perception/image_projection_based_fusion/config/segmentation_pointcloud_fusion.param.yaml @@ -31,10 +31,9 @@ # debug debug_mode: false - filter_scope_min_x: -100 - filter_scope_max_x: 100 - filter_scope_min_y: -100 - filter_scope_max_y: 100 - filter_scope_min_z: -100 - filter_scope_max_z: 100 - image_buffer_size: 15 + filter_scope_min_x: -100.0 + filter_scope_max_x: 100.0 + filter_scope_min_y: -100.0 + filter_scope_max_y: 100.0 + filter_scope_min_z: -100.0 + filter_scope_max_z: 100.0 diff --git a/perception/image_projection_based_fusion/docs/pointpainting-fusion.md b/perception/image_projection_based_fusion/docs/pointpainting-fusion.md index d50a3f97390ca..85e740d95ebd0 100644 --- a/perception/image_projection_based_fusion/docs/pointpainting-fusion.md +++ b/perception/image_projection_based_fusion/docs/pointpainting-fusion.md @@ -33,17 +33,22 @@ The lidar points are projected onto the output of an image-only 2d object detect ### Core Parameters -| Name | Type | Default Value | Description | -| ------------------------------- | ------ | ------------- | ----------------------------------------------------------- | -| `score_threshold` | float | `0.4` | detected objects with score less than threshold are ignored | -| `densification_world_frame_id` | string | `map` | the world frame id to fuse multi-frame pointcloud | -| `densification_num_past_frames` | int | `0` | the number of past frames to fuse with the current frame | -| `trt_precision` | string | `fp16` | TensorRT inference precision: `fp32` or `fp16` | -| `encoder_onnx_path` | string | `""` | path to VoxelFeatureEncoder ONNX file | -| `encoder_engine_path` | string | `""` | path to VoxelFeatureEncoder TensorRT Engine file | -| `head_onnx_path` | string | `""` | path to DetectionHead ONNX file | -| `head_engine_path` | string | `""` | path to DetectionHead TensorRT Engine file | -| `build_only` | bool | `false` | shutdown the node after TensorRT engine file is built | +| Name | Type | Default Value | Description | +| ------------------------------------------------ | ------------ | ------------------------- | ----------------------------------------------------------- | +| `encoder_onnx_path` | string | `""` | path to VoxelFeatureEncoder ONNX file | +| `encoder_engine_path` | string | `""` | path to VoxelFeatureEncoder TensorRT Engine file | +| `head_onnx_path` | string | `""` | path to DetectionHead ONNX file | +| `head_engine_path` | string | `""` | path to DetectionHead TensorRT Engine file | +| `build_only` | bool | `false` | shutdown the node after TensorRT engine file is built | +| `trt_precision` | string | `fp16` | TensorRT inference precision: `fp32` or `fp16` | +| `post_process_params.score_threshold` | double | `0.4` | detected objects with score less than threshold are ignored | +| `post_process_params.yaw_norm_thresholds` | list[double] | [0.3, 0.3, 0.3, 0.3, 0.0] | An array of distance threshold values of norm of yaw [rad]. | +| `post_process_params.iou_nms_target_class_names` | list[string] | ["CAR"] | An array of class names to be target in NMS. | +| `post_process_params.iou_nms_search_distance_2d` | double | 10.0 | A maximum distance value to search the nearest objects. | +| `post_process_params.iou_nms_threshold` | double | 0.1 | A threshold value of NMS using IoU score. | +| `post_process_params.has_twist` | boolean | false | Indicates whether the model outputs twist value. | +| `densification_params.world_frame_id` | string | `map` | the world frame id to fuse multi-frame pointcloud | +| `densification_params.num_past_frames` | int | `1` | the number of past frames to fuse with the current frame | ## Assumptions / Known limits diff --git a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml index 9236d7d789ed1..d2f803f13d376 100644 --- a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml @@ -21,9 +21,10 @@ - - - + + + + @@ -48,6 +49,7 @@ + @@ -89,6 +91,7 @@ + diff --git a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml index 8df1a374b00b6..f624b099fccb3 100644 --- a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml @@ -19,7 +19,7 @@ - + diff --git a/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml index c9da81af9ddb0..f11280b7f7c67 100644 --- a/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml @@ -19,7 +19,7 @@ - + diff --git a/perception/image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml index 046d88d06e2a1..cde06744aca58 100644 --- a/perception/image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml @@ -21,7 +21,7 @@ - + diff --git a/perception/image_projection_based_fusion/launch/segmentation_pointcloud_fusion.launch.xml b/perception/image_projection_based_fusion/launch/segmentation_pointcloud_fusion.launch.xml index 1db2bb20793ac..cf4d104b9e05a 100644 --- a/perception/image_projection_based_fusion/launch/segmentation_pointcloud_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/segmentation_pointcloud_fusion.launch.xml @@ -18,7 +18,7 @@ - + diff --git a/perception/image_projection_based_fusion/package.xml b/perception/image_projection_based_fusion/package.xml index a5b41a30be166..57fe994aedf5a 100644 --- a/perception/image_projection_based_fusion/package.xml +++ b/perception/image_projection_based_fusion/package.xml @@ -36,6 +36,7 @@ tier4_autoware_utils tier4_perception_msgs + ament_cmake_gtest ament_lint_auto autoware_lint_common diff --git a/perception/image_projection_based_fusion/schema/roi_sync.schema.json b/perception/image_projection_based_fusion/schema/fusion_common.schema.json similarity index 97% rename from perception/image_projection_based_fusion/schema/roi_sync.schema.json rename to perception/image_projection_based_fusion/schema/fusion_common.schema.json index 411fb678a49a7..73ee1661adaea 100644 --- a/perception/image_projection_based_fusion/schema/roi_sync.schema.json +++ b/perception/image_projection_based_fusion/schema/fusion_common.schema.json @@ -3,7 +3,7 @@ "title": "Parameters for Synchronization of RoI Fusion Nodes", "type": "object", "definitions": { - "roi_sync": { + "fusion_common": { "type": "object", "properties": { "input_offset_ms": { @@ -74,7 +74,7 @@ "type": "object", "properties": { "ros__parameters": { - "$ref": "#/definitions/roi_sync" + "$ref": "#/definitions/fusion_common" } }, "required": ["ros__parameters"] diff --git a/perception/image_projection_based_fusion/schema/pointpainting.schema.json b/perception/image_projection_based_fusion/schema/pointpainting.schema.json index bc8f0512263b6..57d8bc500f3c6 100644 --- a/perception/image_projection_based_fusion/schema/pointpainting.schema.json +++ b/perception/image_projection_based_fusion/schema/pointpainting.schema.json @@ -6,71 +6,11 @@ "pointpainting": { "type": "object", "properties": { - "model_params": { - "type": "object", - "description": "Parameters for model configuration.", - "properties": { - "class_names": { - "type": "array", - "description": "An array of class names will be predicted.", - "default": ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"], - "uniqueItems": true - }, - "paint_class_names": { - "type": "array", - "description": "An array of class names will be painted by PointPainting", - "default": ["CAR", "BICYCLE", "PEDESTRIAN"], - "uniqueItems": true - }, - "point_feature_size": { - "type": "integer", - "description": "A number of channels of point feature layer.", - "default": 7 - }, - "max_voxel_size": { - "type": "integer", - "description": "A maximum size of voxel grid.", - "default": 40000 - }, - "point_cloud_range": { - "type": "array", - "description": "An array of distance ranges of each class, this must have same length with `class_names`.", - "default": [-121.6, -76.8, -3.0, 121.6, 76.8, 5.0] - }, - "voxel_size": { - "type": "array", - "description": "An array of voxel grid sizes for PointPainting, this must have same length with `paint_class_names`.", - "default": [0.32, 0.32, 8.0] - }, - "down_sample_factor": { - "type": "integer", - "description": "A scale factor of downsampling points", - "default": 1, - "minimum": 1 - }, - "encoder_in_feature_size": { - "type": "integer", - "description": "A size of encoder input feature channels.", - "default": 12 - }, - "yaw_norm_thresholds": { - "type": "array", - "description": "An array of distance threshold values of norm of yaw [rad].", - "default": [0.3, 0.3, 0.3, 0.3, 0.0], - "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.", - "default": false - } - } + "trt_precision": { + "type": "string", + "description": "TensorRT inference precision.", + "default": "fp16", + "enum": ["fp32", "fp16"] }, "densification_params": { "type": "object", @@ -112,7 +52,7 @@ "default": ["CAR"], "uniqueItems": true }, - "iou_search_distance_2d": { + "iou_nms_search_distance_2d": { "type": "number", "description": "A maximum distance value to search the nearest objects.", "default": 10.0, @@ -124,6 +64,23 @@ "default": 0.1, "minimum": 0.0, "maximum": 1.0 + }, + "yaw_norm_thresholds": { + "type": "array", + "description": "An array of distance threshold values of norm of yaw [rad].", + "default": [0.3, 0.3, 0.3, 0.3, 0.0], + "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.", + "default": false } } }, @@ -139,7 +96,7 @@ } } }, - "required": ["model_params", "densification_params", "post_process_params", "omp_params"] + "required": [] } }, "properties": { diff --git a/perception/image_projection_based_fusion/schema/pointpainting_ml_package.schema.json b/perception/image_projection_based_fusion/schema/pointpainting_ml_package.schema.json new file mode 100644 index 0000000000000..0f89d050c1828 --- /dev/null +++ b/perception/image_projection_based_fusion/schema/pointpainting_ml_package.schema.json @@ -0,0 +1,74 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Point Painting ML model", + "type": "object", + "definitions": { + "pointpainting_ml_package": { + "type": "object", + "properties": { + "model_params": { + "type": "object", + "description": "Parameters for model configuration.", + "properties": { + "class_names": { + "type": "array", + "description": "An array of class names will be predicted.", + "default": ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"], + "uniqueItems": true + }, + "paint_class_names": { + "type": "array", + "description": "An array of class names will be painted by PointPainting", + "default": ["CAR", "BICYCLE", "PEDESTRIAN"], + "uniqueItems": true + }, + "point_feature_size": { + "type": "integer", + "description": "A number of channels of point feature layer.", + "default": 7 + }, + "max_voxel_size": { + "type": "integer", + "description": "A maximum size of voxel grid.", + "default": 40000 + }, + "point_cloud_range": { + "type": "array", + "description": "An array of distance ranges of each class, this must have same length with `class_names`.", + "default": [-121.6, -76.8, -3.0, 121.6, 76.8, 5.0] + }, + "voxel_size": { + "type": "array", + "description": "An array of voxel grid sizes for PointPainting, this must have same length with `paint_class_names`.", + "default": [0.32, 0.32, 8.0] + }, + "down_sample_factor": { + "type": "integer", + "description": "A scale factor of downsampling points", + "default": 1, + "minimum": 1 + }, + "encoder_in_feature_size": { + "type": "integer", + "description": "A size of encoder input feature channels.", + "default": 12 + } + } + } + }, + "required": [] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/pointpainting_ml_package" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} 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 c4c5941be5fec..2c33df0b65afc 100644 --- a/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp @@ -102,7 +102,7 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt const float circle_nms_dist_threshold = static_cast( this->declare_parameter("post_process_params.circle_nms_dist_threshold")); const auto yaw_norm_thresholds = - this->declare_parameter>("model_params.yaw_norm_thresholds"); + this->declare_parameter>("post_process_params.yaw_norm_thresholds"); // densification param const std::string densification_world_frame_id = this->declare_parameter("densification_params.world_frame_id"); @@ -140,8 +140,8 @@ 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"); + has_variance_ = this->declare_parameter("model_params.has_variance"); const std::size_t point_feature_size = static_cast( this->declare_parameter("model_params.point_feature_size")); const std::size_t max_voxel_size = diff --git a/perception/image_projection_based_fusion/test/test_calc_iou_functions.cpp b/perception/image_projection_based_fusion/test/test_calc_iou_functions.cpp new file mode 100644 index 0000000000000..1cddef44c0bac --- /dev/null +++ b/perception/image_projection_based_fusion/test/test_calc_iou_functions.cpp @@ -0,0 +1,122 @@ +// 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 "image_projection_based_fusion/utils/geometry.hpp" + +#include + +using image_projection_based_fusion::calcIoU; +using image_projection_based_fusion::calcIoUX; +using image_projection_based_fusion::calcIoUY; + +TEST(GeometryTest, CalcIoU) +{ + sensor_msgs::msg::RegionOfInterest roi1, roi2; + + // Overlapping ROIs + roi1.x_offset = 0; + roi1.y_offset = 0; + roi1.width = 4; + roi1.height = 4; + + roi2.x_offset = 2; + roi2.y_offset = 2; + roi2.width = 4; + roi2.height = 4; + + double iou = calcIoU(roi1, roi2); + EXPECT_NEAR(iou, 1.0 / 7.0, 1e-6); + + // Non-overlapping ROIs + roi2.x_offset = 5; + roi2.y_offset = 5; + + iou = calcIoU(roi1, roi2); + EXPECT_EQ(iou, 0.0); + + // Zero area ROI + roi1.width = 0; + roi1.height = 0; + + iou = calcIoU(roi1, roi2); + EXPECT_EQ(iou, 0.0); +} + +TEST(GeometryTest, CalcIoUX) +{ + sensor_msgs::msg::RegionOfInterest roi1, roi2; + + // Overlapping ROIs on x-axis + roi1.x_offset = 0; + roi1.y_offset = 0; + roi1.width = 4; + roi1.height = 4; + + roi2.x_offset = 2; + roi2.y_offset = 0; + roi2.width = 4; + roi2.height = 4; + + double iou_x = calcIoUX(roi1, roi2); + EXPECT_NEAR(iou_x, 2.0 / 6.0, 1e-6); + + // Non-overlapping ROIs on x-axis + roi2.x_offset = 5; + + iou_x = calcIoUX(roi1, roi2); + EXPECT_EQ(iou_x, 0.0); + + // Zero width ROI + roi1.width = 0; + + iou_x = calcIoUX(roi1, roi2); + EXPECT_EQ(iou_x, 0.0); +} + +TEST(GeometryTest, CalcIoUY) +{ + sensor_msgs::msg::RegionOfInterest roi1, roi2; + + // Overlapping ROIs on y-axis + roi1.x_offset = 0; + roi1.y_offset = 0; + roi1.width = 4; + roi1.height = 4; + + roi2.x_offset = 0; + roi2.y_offset = 2; + roi2.width = 4; + roi2.height = 4; + + double iou_y = calcIoUY(roi1, roi2); + EXPECT_NEAR(iou_y, 2.0 / 6.0, 1e-6); + + // Non-overlapping ROIs on y-axis + roi2.y_offset = 5; + + iou_y = calcIoUY(roi1, roi2); + EXPECT_EQ(iou_y, 0.0); + + // Zero height ROI + roi1.height = 0; + + iou_y = calcIoUY(roi1, roi2); + EXPECT_EQ(iou_y, 0.0); +} + +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/perception/image_projection_based_fusion/test/test_geometry.cpp b/perception/image_projection_based_fusion/test/test_geometry.cpp new file mode 100644 index 0000000000000..ac8160fe89124 --- /dev/null +++ b/perception/image_projection_based_fusion/test/test_geometry.cpp @@ -0,0 +1,206 @@ +// 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 "image_projection_based_fusion/utils/geometry.hpp" + +#include + +TEST(objectToVertices, test_objectToVertices) +{ + // Test `boundingBoxToVertices()` and `cylinderToVertices()` simultaneously + // Test at Shape::BOUNDING_BOX + geometry_msgs::msg::Pose pose; + pose.position.x = 1.0; + pose.position.y = 2.0; + pose.position.z = 3.0; + const double angle = M_PI / 12; + pose.orientation.x = 0.0; + pose.orientation.y = 0.0; + pose.orientation.z = std::sin(angle); + pose.orientation.w = std::cos(angle); + { + autoware_auto_perception_msgs::msg::Shape shape; + shape.type = 0; + shape.dimensions.x = 4.0; + shape.dimensions.y = 6.0; + shape.dimensions.z = 8.0; + std::vector vertices; + + image_projection_based_fusion::objectToVertices(pose, shape, vertices); + + EXPECT_FALSE(vertices.empty()); + EXPECT_NEAR(vertices.at(0).x(), 1.2320508075688772935274, 1e-6); + EXPECT_NEAR(vertices.at(0).y(), 5.598076211353315940291, 1e-6); + EXPECT_NEAR(vertices.at(0).z(), -1.0, 1e-6); + EXPECT_NEAR(vertices.at(7).x(), -2.232050807568877293527, 1e-6); + EXPECT_NEAR(vertices.at(7).y(), 3.598076211353315940291, 1e-6); + EXPECT_NEAR(vertices.at(7).z(), 7.0, 1e-6); + } + + { + // Test at Shape::CYLINDER + autoware_auto_perception_msgs::msg::Shape shape; + shape.type = 1; + shape.dimensions.x = 4.0; + shape.dimensions.y = 6.0; + shape.dimensions.z = 8.0; + std::vector vertices; + + image_projection_based_fusion::objectToVertices(pose, shape, vertices); + + EXPECT_FALSE(vertices.empty()); + EXPECT_NEAR(vertices.at(0).x(), 2.732050807568877293528, 1e-6); + EXPECT_NEAR(vertices.at(0).y(), 3.0, 1e-6); + EXPECT_NEAR(vertices.at(0).z(), 7.0, 1e-6); + EXPECT_NEAR(vertices.at(11).x(), 2.732050807568877293528, 1e-6); + EXPECT_NEAR(vertices.at(11).y(), 1.0, 1e-6); + EXPECT_NEAR(vertices.at(11).z(), -1.0, 1e-6); + } + + { + // Test at Shape::POLYGON (Nothing to do) + autoware_auto_perception_msgs::msg::Shape shape; + shape.type = 2; + std::vector vertices; + + image_projection_based_fusion::objectToVertices(pose, shape, vertices); + + EXPECT_TRUE(vertices.empty()); + } +} + +TEST(transformPoints, test_transformPoints) +{ + std::vector input_points; + Eigen::Vector3d point(0.0, 0.0, 0.0); + input_points.push_back(point); + Eigen::Translation translation(1.0, 1.0, 1.0); + Eigen::Matrix3d rotation = (Eigen::AngleAxisd(M_PI / 4, Eigen::Vector3d::UnitX()) * + Eigen::AngleAxisd(M_PI / 4, Eigen::Vector3d::UnitY()) * + Eigen::AngleAxisd(M_PI / 4, Eigen::Vector3d::UnitZ())) + .toRotationMatrix(); + Eigen::Affine3d affine_transform = rotation * translation; + std::vector output_points; + + image_projection_based_fusion::transformPoints(input_points, affine_transform, output_points); + + EXPECT_FALSE(output_points.empty()); + EXPECT_NEAR(output_points.at(0).x(), 0.7071067811865475244008, 1e-6); + EXPECT_NEAR(output_points.at(0).y(), 0.5, 1e-6); + EXPECT_NEAR(output_points.at(0).z(), 1.5, 1e-6); +} + +TEST(is_inside, test_is_inside) +{ + // Test default pattern + sensor_msgs::msg::RegionOfInterest outer; + outer.x_offset = 30; + outer.y_offset = 40; + outer.height = 400; + outer.width = 300; + const double outer_offset_scale = 1.0; + { + sensor_msgs::msg::RegionOfInterest inner; + inner.x_offset = 31; + inner.y_offset = 41; + inner.height = 399; + inner.width = 299; + + const bool inside_flag = + image_projection_based_fusion::is_inside(outer, inner, outer_offset_scale); + + EXPECT_TRUE(inside_flag); + } + + { + // Test left-top outside pattern + sensor_msgs::msg::RegionOfInterest inner; + inner.x_offset = 29; + inner.y_offset = 39; + + const bool inside_flag = + image_projection_based_fusion::is_inside(outer, inner, outer_offset_scale); + + EXPECT_FALSE(inside_flag); + } + + { + // Test right-bottom outside pattern + sensor_msgs::msg::RegionOfInterest inner; + inner.x_offset = 31; + inner.y_offset = 41; + inner.height = 401; + inner.width = 301; + + const bool inside_flag = + image_projection_based_fusion::is_inside(outer, inner, outer_offset_scale); + + EXPECT_FALSE(inside_flag); + } +} + +TEST(sanitizeROI, test_sanitizeROI) +{ + { + // Test default pattern + sensor_msgs::msg::RegionOfInterest roi; + roi.x_offset = 10; + roi.y_offset = 20; + roi.height = 200; + roi.width = 100; + int height = 400; // image height + int width = 300; // image width + + image_projection_based_fusion::sanitizeROI(roi, width, height); + + EXPECT_EQ(roi.height, 200); + EXPECT_EQ(roi.width, 100); + } + + { + // Test pattern that x_offset or y_offset is not in image + sensor_msgs::msg::RegionOfInterest roi; + roi.x_offset = 100; + roi.y_offset = 200; + int height = 100; + int width = 50; + + image_projection_based_fusion::sanitizeROI(roi, width, height); + + EXPECT_EQ(roi.height, 0); + EXPECT_EQ(roi.width, 0); + } + + { + // Test patten that roi does not fit within image + sensor_msgs::msg::RegionOfInterest roi; + roi.x_offset = 10; + roi.y_offset = 20; + roi.height = 500; + roi.width = 400; + int height = 100; + int width = 50; + + image_projection_based_fusion::sanitizeROI(roi, width, height); + + EXPECT_EQ(roi.height, 80); + EXPECT_EQ(roi.width, 40); + } +} + +int main(int argc, char * argv[]) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/perception/image_projection_based_fusion/test/test_utils.cpp b/perception/image_projection_based_fusion/test/test_utils.cpp new file mode 100644 index 0000000000000..e578ce1987cc3 --- /dev/null +++ b/perception/image_projection_based_fusion/test/test_utils.cpp @@ -0,0 +1,170 @@ +// 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 +#include + +#include + +using autoware_point_types::PointXYZI; + +void setPointCloud2Fields(sensor_msgs::msg::PointCloud2 & pointcloud) +{ + pointcloud.fields.resize(4); + pointcloud.fields[0].name = "x"; + pointcloud.fields[1].name = "y"; + pointcloud.fields[2].name = "z"; + pointcloud.fields[3].name = "intensity"; + pointcloud.fields[0].offset = 0; + pointcloud.fields[1].offset = 4; + pointcloud.fields[2].offset = 8; + pointcloud.fields[3].offset = 12; + pointcloud.fields[0].datatype = sensor_msgs::msg::PointField::FLOAT32; + pointcloud.fields[1].datatype = sensor_msgs::msg::PointField::FLOAT32; + pointcloud.fields[2].datatype = sensor_msgs::msg::PointField::FLOAT32; + pointcloud.fields[3].datatype = sensor_msgs::msg::PointField::FLOAT32; + pointcloud.fields[0].count = 1; + pointcloud.fields[1].count = 1; + pointcloud.fields[2].count = 1; + pointcloud.fields[3].count = 1; + pointcloud.height = 1; + pointcloud.point_step = 16; + pointcloud.is_bigendian = false; + pointcloud.is_dense = true; + pointcloud.header.frame_id = "dummy_frame_id"; + pointcloud.header.stamp.sec = 0; + pointcloud.header.stamp.nanosec = 0; +} + +// Test case 1: Test case when the input pointcloud is empty +TEST(UtilsTest, closest_cluster_empty_cluster_test_case1) +{ + sensor_msgs::msg::PointCloud2 pointcloud; + setPointCloud2Fields(pointcloud); + pointcloud.data.resize(0); + pointcloud.width = 0; + pointcloud.row_step = 0; + + pcl::PointXYZ center; + center.x = 0.0; + center.y = 0.0; + center.z = 0.0; + + // testing closest_cluster function + double cluster_2d_tolerance = 0.5; + int min_cluster_size = 3; + sensor_msgs::msg::PointCloud2 output_cluster; + image_projection_based_fusion::closest_cluster( + pointcloud, cluster_2d_tolerance, min_cluster_size, center, output_cluster); + EXPECT_EQ(output_cluster.data.size(), std::size_t(0)); +} + +// Test case 2: Test case when the input pointcloud as one cluster +TEST(UtilsTest, closest_cluster_test_case2) +{ + sensor_msgs::msg::PointCloud2 pointcloud; + setPointCloud2Fields(pointcloud); + std::vector dummy_x = {0.0, 0.1, 0.2}; + pointcloud.data.resize(dummy_x.size() * pointcloud.point_step); + size_t global_offset = 0; + for (auto x : dummy_x) { + PointXYZI point; + point.x = x; + point.y = 0.0; + point.z = 0.0; + point.intensity = 0.0; + memcpy(&pointcloud.data[global_offset], &point, pointcloud.point_step); + global_offset += pointcloud.point_step; + } + pcl::PointXYZ center; + center.x = 0.0; + center.y = 0.0; + center.z = 0.0; + + // testing closest_cluster function + double cluster_2d_tolerance = 0.5; + int min_cluster_size = 3; + sensor_msgs::msg::PointCloud2 output_cluster; + image_projection_based_fusion::closest_cluster( + pointcloud, cluster_2d_tolerance, min_cluster_size, center, output_cluster); + EXPECT_EQ(output_cluster.data.size(), dummy_x.size() * pointcloud.point_step); +} + +// Test case 3: Test case when the input pointcloud as two clusters +TEST(UtilsTest, closest_cluster_test_case3) +{ + sensor_msgs::msg::PointCloud2 pointcloud; + setPointCloud2Fields(pointcloud); + std::vector dummy_x = {0.0, 0.1, 0.2, 1.0, 1.1, 1.2, 1.21, 1.22}; + pointcloud.data.resize(dummy_x.size() * pointcloud.point_step); + size_t global_offset = 0; + for (auto x : dummy_x) { + PointXYZI point; + point.x = x; + point.y = 0.0; + point.z = 0.0; + point.intensity = 0.0; + memcpy(&pointcloud.data[global_offset], &point, pointcloud.point_step); + global_offset += pointcloud.point_step; + } + pcl::PointXYZ center; + center.x = 0.0; + center.y = 0.0; + center.z = 0.0; + + // testing closest_cluster function + double cluster_2d_tolerance = 0.5; + int min_cluster_size = 3; + sensor_msgs::msg::PointCloud2 output_cluster; + image_projection_based_fusion::closest_cluster( + pointcloud, cluster_2d_tolerance, min_cluster_size, center, output_cluster); + EXPECT_EQ(output_cluster.data.size(), 3 * pointcloud.point_step); +} + +// Test case 4: Test case when the input pointcloud as two clusters +TEST(UtilsTest, closest_cluster_test_case4) +{ + sensor_msgs::msg::PointCloud2 pointcloud; + setPointCloud2Fields(pointcloud); + std::vector dummy_x = {0.0, 0.1, 1.0, 1.01, 1.1, 1.2, 1.21, 1.22}; + pointcloud.data.resize(dummy_x.size() * pointcloud.point_step); + size_t global_offset = 0; + for (auto x : dummy_x) { + PointXYZI point; + point.x = x; + point.y = 0.0; + point.z = 0.0; + point.intensity = 0.0; + memcpy(&pointcloud.data[global_offset], &point, pointcloud.point_step); + global_offset += pointcloud.point_step; + } + pcl::PointXYZ center; + center.x = 0.0; + center.y = 0.0; + center.z = 0.0; + + // testing closest_cluster function + double cluster_2d_tolerance = 0.5; + int min_cluster_size = 3; + sensor_msgs::msg::PointCloud2 output_cluster; + image_projection_based_fusion::closest_cluster( + pointcloud, cluster_2d_tolerance, min_cluster_size, center, output_cluster); + EXPECT_EQ(output_cluster.data.size(), 6 * pointcloud.point_step); +} + +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/perception/lidar_centerpoint/CMakeLists.txt b/perception/lidar_centerpoint/CMakeLists.txt index 8fab65ef6b4d7..8a7f4c6107c67 100644 --- a/perception/lidar_centerpoint/CMakeLists.txt +++ b/perception/lidar_centerpoint/CMakeLists.txt @@ -147,6 +147,64 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) TARGETS centerpoint_cuda_lib DESTINATION lib ) + + if(BUILD_TESTING) + find_package(ament_cmake_gtest REQUIRED) + ament_auto_add_gtest(test_detection_class_remapper + test/test_detection_class_remapper.cpp + ) + ament_auto_add_gtest(test_ros_utils + test/test_ros_utils.cpp + ) + ament_auto_add_gtest(test_nms + test/test_nms.cpp + ) + ament_auto_add_gtest(test_voxel_generator + test/test_voxel_generator.cpp + ) + + add_executable(test_preprocess_kernel + test/test_preprocess_kernel.cpp + lib/utils.cpp + ) + + target_include_directories(test_preprocess_kernel PUBLIC + ${test_preprocess_kernel_SOURCE_DIR} + ) + + target_link_libraries(test_preprocess_kernel + centerpoint_cuda_lib + gtest + gtest_main + ) + + ament_add_test(test_preprocess_kernel + GENERATE_RESULT_FOR_RETURN_CODE_ZERO + COMMAND "$" + ) + + add_executable(test_postprocess_kernel + test/test_postprocess_kernel.cpp + lib/utils.cpp + ) + + target_include_directories(test_postprocess_kernel PUBLIC + ${test_postprocess_kernel_SOURCE_DIR} + ) + + target_link_libraries(test_postprocess_kernel + centerpoint_cuda_lib + gtest + gtest_main + ) + + ament_add_test(test_postprocess_kernel + GENERATE_RESULT_FOR_RETURN_CODE_ZERO + COMMAND "$" + ) + + endif() + else() find_package(ament_cmake_auto REQUIRED) ament_auto_find_build_dependencies() diff --git a/perception/lidar_centerpoint/README.md b/perception/lidar_centerpoint/README.md index ed71349d5bd7f..09cee5266760c 100644 --- a/perception/lidar_centerpoint/README.md +++ b/perception/lidar_centerpoint/README.md @@ -30,20 +30,22 @@ We trained the models using . ### Core Parameters -| Name | Type | Default Value | Description | -| ------------------------------- | ------------ | ------------- | ------------------------------------------------------------- | -| `score_threshold` | float | `0.4` | detected objects with score less than threshold are ignored | -| `densification_world_frame_id` | string | `map` | the world frame id to fuse multi-frame pointcloud | -| `densification_num_past_frames` | int | `1` | the number of past frames to fuse with the current frame | -| `trt_precision` | string | `fp16` | TensorRT inference precision: `fp32` or `fp16` | -| `encoder_onnx_path` | string | `""` | path to VoxelFeatureEncoder ONNX file | -| `encoder_engine_path` | string | `""` | path to VoxelFeatureEncoder TensorRT Engine file | -| `head_onnx_path` | string | `""` | path to DetectionHead ONNX file | -| `head_engine_path` | string | `""` | path to DetectionHead TensorRT Engine file | -| `nms_iou_target_class_names` | list[string] | - | target classes for IoU-based Non Maximum Suppression | -| `nms_iou_search_distance_2d` | double | - | If two objects are farther than the value, NMS isn't applied. | -| `nms_iou_threshold` | double | - | IoU threshold for the IoU-based Non Maximum Suppression | -| `build_only` | bool | `false` | shutdown the node after TensorRT engine file is built | +| Name | Type | Default Value | Description | +| ------------------------------------------------ | ------------ | ------------------------- | ------------------------------------------------------------- | +| `encoder_onnx_path` | string | `""` | path to VoxelFeatureEncoder ONNX file | +| `encoder_engine_path` | string | `""` | path to VoxelFeatureEncoder TensorRT Engine file | +| `head_onnx_path` | string | `""` | path to DetectionHead ONNX file | +| `head_engine_path` | string | `""` | path to DetectionHead TensorRT Engine file | +| `build_only` | bool | `false` | shutdown the node after TensorRT engine file is built | +| `trt_precision` | string | `fp16` | TensorRT inference precision: `fp32` or `fp16` | +| `post_process_params.score_threshold` | double | `0.4` | detected objects with score less than threshold are ignored | +| `post_process_params.yaw_norm_thresholds` | list[double] | [0.3, 0.3, 0.3, 0.3, 0.0] | An array of distance threshold values of norm of yaw [rad]. | +| `post_process_params.iou_nms_target_class_names` | list[string] | - | target classes for IoU-based Non Maximum Suppression | +| `post_process_params.iou_nms_search_distance_2d` | double | - | If two objects are farther than the value, NMS isn't applied. | +| `post_process_params.iou_nms_threshold` | double | - | IoU threshold for the IoU-based Non Maximum Suppression | +| `post_process_params.has_twist` | boolean | false | Indicates whether the model outputs twist value. | +| `densification_params.world_frame_id` | string | `map` | the world frame id to fuse multi-frame pointcloud | +| `densification_params.num_past_frames` | int | `1` | the number of past frames to fuse with the current frame | ### The `build_only` option diff --git a/perception/lidar_centerpoint/config/centerpoint.param.yaml b/perception/lidar_centerpoint/config/centerpoint.param.yaml index 38c57285e552d..17ed9a447cdb8 100644 --- a/perception/lidar_centerpoint/config/centerpoint.param.yaml +++ b/perception/lidar_centerpoint/config/centerpoint.param.yaml @@ -1,27 +1,19 @@ /**: 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: false - has_twist: false - 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" + trt_precision: fp16 + post_process_params: + # 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 + score_threshold: 0.35 + yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] + densification_params: + world_frame_id: map + num_past_frames: 1 diff --git a/perception/lidar_centerpoint/config/centerpoint_ml_package.param.yaml b/perception/lidar_centerpoint/config/centerpoint_ml_package.param.yaml new file mode 100644 index 0000000000000..c8d17890e33be --- /dev/null +++ b/perception/lidar_centerpoint/config/centerpoint_ml_package.param.yaml @@ -0,0 +1,12 @@ +/**: + ros__parameters: + model_params: + 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 + has_variance: false + has_twist: false diff --git a/perception/lidar_centerpoint/config/centerpoint_sigma.param.yaml b/perception/lidar_centerpoint/config/centerpoint_sigma.param.yaml deleted file mode 100644 index c217f6321381a..0000000000000 --- a/perception/lidar_centerpoint/config/centerpoint_sigma.param.yaml +++ /dev/null @@ -1,27 +0,0 @@ -/**: - 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_sigma_ml_package.param.yaml b/perception/lidar_centerpoint/config/centerpoint_sigma_ml_package.param.yaml new file mode 100644 index 0000000000000..c8d17890e33be --- /dev/null +++ b/perception/lidar_centerpoint/config/centerpoint_sigma_ml_package.param.yaml @@ -0,0 +1,12 @@ +/**: + ros__parameters: + model_params: + 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 + has_variance: false + has_twist: false diff --git a/perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml b/perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml index 35e11e61e9634..17ed9a447cdb8 100644 --- a/perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml +++ b/perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml @@ -1,27 +1,19 @@ /**: 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: 2 - 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: false - has_twist: false - 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" + trt_precision: fp16 + post_process_params: + # 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 + score_threshold: 0.35 + yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] + densification_params: + world_frame_id: map + num_past_frames: 1 diff --git a/perception/lidar_centerpoint/config/centerpoint_tiny_ml_package.param.yaml b/perception/lidar_centerpoint/config/centerpoint_tiny_ml_package.param.yaml new file mode 100644 index 0000000000000..2a3f9c8e75290 --- /dev/null +++ b/perception/lidar_centerpoint/config/centerpoint_tiny_ml_package.param.yaml @@ -0,0 +1,12 @@ +/**: + ros__parameters: + model_params: + 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: 2 + encoder_in_feature_size: 9 + has_variance: false + has_twist: false diff --git a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml index 5489af2c8fb60..950dfa7f5b290 100644 --- a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml +++ b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml @@ -6,7 +6,8 @@ - + + @@ -18,6 +19,7 @@ + @@ -30,6 +32,7 @@ + diff --git a/perception/lidar_centerpoint/lib/preprocess/preprocess_kernel.cu b/perception/lidar_centerpoint/lib/preprocess/preprocess_kernel.cu index 118e31f892d72..218aaee125c02 100644 --- a/perception/lidar_centerpoint/lib/preprocess/preprocess_kernel.cu +++ b/perception/lidar_centerpoint/lib/preprocess/preprocess_kernel.cu @@ -78,6 +78,11 @@ cudaError_t generateVoxels_random_launch( { dim3 blocks((points_size + 256 - 1) / 256); dim3 threads(256); + + if (blocks.x == 0) { + return cudaGetLastError(); + } + generateVoxels_random_kernel<<>>( points, points_size, min_x_range, max_x_range, min_y_range, max_y_range, min_z_range, max_z_range, pillar_x_size, pillar_y_size, pillar_z_size, grid_y_size, grid_x_size, mask, diff --git a/perception/lidar_centerpoint/schema/centerpoint.schemal.json b/perception/lidar_centerpoint/schema/centerpoint.schemal.json new file mode 100644 index 0000000000000..b11c115cc2466 --- /dev/null +++ b/perception/lidar_centerpoint/schema/centerpoint.schemal.json @@ -0,0 +1,98 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Lidar Centerpoint Node", + "type": "object", + "definitions": { + "centerpoint": { + "type": "object", + "properties": { + "trt_precision": { + "type": "string", + "description": "TensorRT inference precision.", + "default": "fp16", + "enum": ["fp32", "fp16"] + }, + "post_process_params": { + "type": "object", + "properties": { + "score_threshold": { + "type": "number", + "description": "A threshold value of existence probability score, all of objects with score less than this threshold are ignored.", + "default": 0.35, + "minimum": 0.0, + "maximum": 1.0 + }, + "yaw_norm_thresholds": { + "type": "array", + "description": "An array of distance threshold values of norm of yaw [rad].", + "default": [0.3, 0.3, 0.3, 0.3, 0.0], + "minimum": 0.0, + "maximum": 1.0 + }, + "circle_nms_dist_threshold": { + "type": "number", + "description": "", + "default": 0.5, + "minimum": 0.0, + "maximum": 1.0 + }, + "iou_nms_target_class_names": { + "type": "array", + "description": "An array of class names to be target in NMS.", + "default": ["CAR"], + "uniqueItems": true + }, + "iou_nms_search_distance_2d": { + "type": "number", + "description": "A maximum distance value to search the nearest objects.", + "default": 10.0, + "minimum": 0.0 + }, + "iou_nms_threshold": { + "type": "number", + "description": "A threshold value of NMS using IoU score.", + "default": 0.1, + "minimum": 0.0, + "maximum": 1.0 + }, + "has_twist": { + "type": "boolean", + "description": "Indicates whether the model outputs twist value.", + "default": false + } + } + }, + "densification_params": { + "type": "object", + "description": "Parameters for pointcloud densification.", + "properties": { + "world_frame_id": { + "type": "string", + "description": "A name of frame id where world coordinates system is defined with respect to.", + "default": "map" + }, + "num_past_frames": { + "type": "integer", + "description": "A number of past frames to be considered as same input frame.", + "default": 1, + "minimum": 0 + } + } + } + }, + "required": ["post_process_params", "densification_params"] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/centerpoint" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/perception/lidar_centerpoint/schema/centerpoint_ml_package.schema.json b/perception/lidar_centerpoint/schema/centerpoint_ml_package.schema.json new file mode 100644 index 0000000000000..2c5655c6201ed --- /dev/null +++ b/perception/lidar_centerpoint/schema/centerpoint_ml_package.schema.json @@ -0,0 +1,68 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Centerpoint ML model", + "type": "object", + "definitions": { + "centerpoint_ml_package": { + "type": "object", + "properties": { + "model_params": { + "type": "object", + "description": "Parameters for model configuration.", + "properties": { + "class_names": { + "type": "array", + "description": "An array of class names will be predicted.", + "default": ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"], + "uniqueItems": true + }, + "point_feature_size": { + "type": "integer", + "description": "A number of channels of point feature layer.", + "default": 4 + }, + "max_voxel_size": { + "type": "integer", + "description": "A maximum size of voxel grid.", + "default": 40000 + }, + "point_cloud_range": { + "type": "array", + "description": "An array of distance ranges of each class, this must have same length with `class_names`.", + "default": [-76.8, -76.8, -4.0, 76.8, 76.8, 6.0] + }, + "voxel_size": { + "type": "array", + "description": "An array of voxel grid sizes for PointPainting, this must have same length with `paint_class_names`.", + "default": [0.32, 0.32, 10.0] + }, + "down_sample_factor": { + "type": "integer", + "description": "A scale factor of downsampling points", + "default": 1, + "minimum": 1 + }, + "encoder_in_feature_size": { + "type": "integer", + "description": "A size of encoder input feature channels.", + "default": 9 + } + } + } + }, + "required": ["model_params"] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/centerpoint_ml_package" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/perception/lidar_centerpoint/schema/centerpoint_tiny_ml_package.schema.json b/perception/lidar_centerpoint/schema/centerpoint_tiny_ml_package.schema.json new file mode 100644 index 0000000000000..55329e21ea8ab --- /dev/null +++ b/perception/lidar_centerpoint/schema/centerpoint_tiny_ml_package.schema.json @@ -0,0 +1,68 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Centerpoint Tiny ML model", + "type": "object", + "definitions": { + "centerpoint_tiny_ml_package": { + "type": "object", + "properties": { + "model_params": { + "type": "object", + "description": "Parameters for model configuration.", + "properties": { + "class_names": { + "type": "array", + "description": "An array of class names will be predicted.", + "default": ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"], + "uniqueItems": true + }, + "point_feature_size": { + "type": "integer", + "description": "A number of channels of point feature layer.", + "default": 4 + }, + "max_voxel_size": { + "type": "integer", + "description": "A maximum size of voxel grid.", + "default": 40000 + }, + "point_cloud_range": { + "type": "array", + "description": "An array of distance ranges of each class, this must have same length with `class_names`.", + "default": [-76.8, -76.8, -4.0, 76.8, 76.8, 6.0] + }, + "voxel_size": { + "type": "array", + "description": "An array of voxel grid sizes for PointPainting, this must have same length with `paint_class_names`.", + "default": [0.32, 0.32, 10.0] + }, + "down_sample_factor": { + "type": "integer", + "description": "A scale factor of downsampling points", + "default": 2, + "minimum": 1 + }, + "encoder_in_feature_size": { + "type": "integer", + "description": "A size of encoder input feature channels.", + "default": 9 + } + } + } + }, + "required": ["model_params"] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/centerpoint_tiny_ml_package" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/perception/lidar_centerpoint/src/node.cpp b/perception/lidar_centerpoint/src/node.cpp index 0606a2ec55c9e..d0abf72d888d3 100644 --- a/perception/lidar_centerpoint/src/node.cpp +++ b/perception/lidar_centerpoint/src/node.cpp @@ -39,34 +39,35 @@ LidarCenterPointNode::LidarCenterPointNode(const rclcpp::NodeOptions & node_opti : Node("lidar_center_point", node_options), tf_buffer_(this->get_clock()) { const float score_threshold = - static_cast(this->declare_parameter("score_threshold", 0.35)); - const float circle_nms_dist_threshold = - static_cast(this->declare_parameter("circle_nms_dist_threshold")); + static_cast(this->declare_parameter("post_process_params.score_threshold")); + const float circle_nms_dist_threshold = static_cast( + this->declare_parameter("post_process_params.circle_nms_dist_threshold")); const auto yaw_norm_thresholds = - this->declare_parameter>("yaw_norm_thresholds"); + this->declare_parameter>("post_process_params.yaw_norm_thresholds"); const std::string densification_world_frame_id = - this->declare_parameter("densification_world_frame_id", "map"); + this->declare_parameter("densification_params.world_frame_id"); const int densification_num_past_frames = - this->declare_parameter("densification_num_past_frames", 1); - const std::string trt_precision = this->declare_parameter("trt_precision", "fp16"); + this->declare_parameter("densification_params.num_past_frames"); + const std::string trt_precision = this->declare_parameter("trt_precision"); const std::string encoder_onnx_path = this->declare_parameter("encoder_onnx_path"); const std::string encoder_engine_path = this->declare_parameter("encoder_engine_path"); 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_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")); + class_names_ = this->declare_parameter>("model_params.class_names"); + 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")); + has_variance_ = this->declare_parameter("model_params.has_variance"); const std::size_t max_voxel_size = - static_cast(this->declare_parameter("max_voxel_size")); - const auto point_cloud_range = this->declare_parameter>("point_cloud_range"); - const auto voxel_size = this->declare_parameter>("voxel_size"); - const std::size_t downsample_factor = - static_cast(this->declare_parameter("downsample_factor")); - const std::size_t encoder_in_feature_size = - static_cast(this->declare_parameter("encoder_in_feature_size")); + static_cast(this->declare_parameter("model_params.max_voxel_size")); + const auto point_cloud_range = + this->declare_parameter>("model_params.point_cloud_range"); + const auto voxel_size = this->declare_parameter>("model_params.voxel_size"); + const std::size_t downsample_factor = static_cast( + this->declare_parameter("model_params.downsample_factor")); + const std::size_t encoder_in_feature_size = static_cast( + this->declare_parameter("model_params.encoder_in_feature_size")); const auto allow_remapping_by_area_matrix = this->declare_parameter>("allow_remapping_by_area_matrix"); const auto min_area_matrix = this->declare_parameter>("min_area_matrix"); @@ -78,10 +79,11 @@ LidarCenterPointNode::LidarCenterPointNode(const rclcpp::NodeOptions & node_opti { NMSParams p; p.nms_type_ = NMS_TYPE::IoU_BEV; - p.target_class_names_ = - this->declare_parameter>("iou_nms_target_class_names"); - p.search_distance_2d_ = this->declare_parameter("iou_nms_search_distance_2d"); - p.iou_threshold_ = this->declare_parameter("iou_nms_threshold"); + p.target_class_names_ = this->declare_parameter>( + "post_process_params.iou_nms_target_class_names"); + p.search_distance_2d_ = + this->declare_parameter("post_process_params.iou_nms_search_distance_2d"); + p.iou_threshold_ = this->declare_parameter("post_process_params.iou_nms_threshold"); iou_bev_nms_.setParameters(p); } diff --git a/perception/lidar_centerpoint/test/test_detection_class_remapper.cpp b/perception/lidar_centerpoint/test/test_detection_class_remapper.cpp new file mode 100644 index 0000000000000..6559736ede198 --- /dev/null +++ b/perception/lidar_centerpoint/test/test_detection_class_remapper.cpp @@ -0,0 +1,92 @@ +// 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 + +#include + +TEST(DetectionClassRemapperTest, MapClasses) +{ + centerpoint::DetectionClassRemapper remapper; + + // Set up the parameters for the remapper + // Labels: CAR, TRUCK, TRAILER + std::vector allow_remapping_by_area_matrix = { + 0, 0, 0, // CAR cannot be remapped + 0, 0, 1, // TRUCK can be remapped to TRAILER + 0, 1, 0 // TRAILER can be remapped to TRUCK + }; + std::vector min_area_matrix = {0.0, 0.0, 0.0, 0.0, 0.0, 10.0, 0.0, 0.0, 0.0}; + std::vector max_area_matrix = {0.0, 0.0, 0.0, 0.0, 0.0, 999.0, 0.0, 10.0, 0.0}; + + remapper.setParameters(allow_remapping_by_area_matrix, min_area_matrix, max_area_matrix); + + // Create a DetectedObjects message with some objects + autoware_auto_perception_msgs::msg::DetectedObjects msg; + + // CAR with area 4.0, which is out of the range for remapping + autoware_auto_perception_msgs::msg::DetectedObject obj1; + autoware_auto_perception_msgs::msg::ObjectClassification obj1_classification; + obj1.shape.dimensions.x = 2.0; + obj1.shape.dimensions.y = 2.0; + obj1_classification.label = 0; + obj1_classification.probability = 1.0; + obj1.classification = {obj1_classification}; + msg.objects.push_back(obj1); + + // TRUCK with area 16.0, which is in the range for remapping to TRAILER + autoware_auto_perception_msgs::msg::DetectedObject obj2; + autoware_auto_perception_msgs::msg::ObjectClassification obj2_classification; + obj2.shape.dimensions.x = 8.0; + obj2.shape.dimensions.y = 2.0; + obj2_classification.label = 1; + obj2_classification.probability = 1.0; + obj2.classification = {obj2_classification}; + msg.objects.push_back(obj2); + + // TRAILER with area 9.0, which is in the range for remapping to TRUCK + autoware_auto_perception_msgs::msg::DetectedObject obj3; + autoware_auto_perception_msgs::msg::ObjectClassification obj3_classification; + obj3.shape.dimensions.x = 3.0; + obj3.shape.dimensions.y = 3.0; + obj3_classification.label = 2; + obj3_classification.probability = 1.0; + obj3.classification = {obj3_classification}; + msg.objects.push_back(obj3); + + // TRAILER with area 12.0, which is out of the range for remapping + autoware_auto_perception_msgs::msg::DetectedObject obj4; + autoware_auto_perception_msgs::msg::ObjectClassification obj4_classification; + obj4.shape.dimensions.x = 4.0; + obj4.shape.dimensions.y = 3.0; + obj4_classification.label = 2; + obj4_classification.probability = 1.0; + obj4.classification = {obj4_classification}; + msg.objects.push_back(obj4); + + // Call the mapClasses function + remapper.mapClasses(msg); + + // Check the remapped labels + EXPECT_EQ(msg.objects[0].classification[0].label, 0); + EXPECT_EQ(msg.objects[1].classification[0].label, 2); + EXPECT_EQ(msg.objects[2].classification[0].label, 1); + EXPECT_EQ(msg.objects[3].classification[0].label, 2); +} + +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/perception/lidar_centerpoint/test/test_nms.cpp b/perception/lidar_centerpoint/test/test_nms.cpp new file mode 100644 index 0000000000000..bf443d8d3ad0f --- /dev/null +++ b/perception/lidar_centerpoint/test/test_nms.cpp @@ -0,0 +1,121 @@ +// 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 "lidar_centerpoint/postprocess/non_maximum_suppression.hpp" + +#include + +TEST(NonMaximumSuppressionTest, Apply) +{ + centerpoint::NonMaximumSuppression nms; + centerpoint::NMSParams params; + params.search_distance_2d_ = 1.0; + params.iou_threshold_ = 0.2; + params.nms_type_ = centerpoint::NMS_TYPE::IoU_BEV; + params.target_class_names_ = {"CAR"}; + nms.setParameters(params); + + std::vector input_objects(4); + + // Object 1 + autoware_auto_perception_msgs::msg::ObjectClassification obj1_classification; + obj1_classification.label = 0; // Assuming "car" has label 0 + obj1_classification.probability = 1.0; + input_objects[0].classification = {obj1_classification}; // Assuming "car" has label 0 + input_objects[0].kinematics.pose_with_covariance.pose.position.x = 0.0; + input_objects[0].kinematics.pose_with_covariance.pose.position.y = 0.0; + input_objects[0].kinematics.pose_with_covariance.pose.orientation.x = 0.0; + input_objects[0].kinematics.pose_with_covariance.pose.orientation.y = 0.0; + input_objects[0].kinematics.pose_with_covariance.pose.orientation.z = 0.0; + input_objects[0].kinematics.pose_with_covariance.pose.orientation.w = 1.0; + input_objects[0].shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; + input_objects[0].shape.dimensions.x = 4.0; + input_objects[0].shape.dimensions.y = 2.0; + + // Object 2 (overlaps with Object 1) + autoware_auto_perception_msgs::msg::ObjectClassification obj2_classification; + obj2_classification.label = 0; // Assuming "car" has label 0 + obj2_classification.probability = 1.0; + input_objects[1].classification = {obj2_classification}; // Assuming "car" has label 0 + input_objects[1].kinematics.pose_with_covariance.pose.position.x = 0.5; + input_objects[1].kinematics.pose_with_covariance.pose.position.y = 0.5; + input_objects[1].kinematics.pose_with_covariance.pose.orientation.x = 0.0; + input_objects[1].kinematics.pose_with_covariance.pose.orientation.y = 0.0; + input_objects[1].kinematics.pose_with_covariance.pose.orientation.z = 0.0; + input_objects[1].kinematics.pose_with_covariance.pose.orientation.w = 1.0; + input_objects[1].shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; + input_objects[1].shape.dimensions.x = 4.0; + input_objects[1].shape.dimensions.y = 2.0; + + // Object 3 + autoware_auto_perception_msgs::msg::ObjectClassification obj3_classification; + obj3_classification.label = 0; // Assuming "car" has label 0 + obj3_classification.probability = 1.0; + input_objects[2].classification = {obj3_classification}; // Assuming "car" has label 0 + input_objects[2].kinematics.pose_with_covariance.pose.position.x = 5.0; + input_objects[2].kinematics.pose_with_covariance.pose.position.y = 5.0; + input_objects[2].kinematics.pose_with_covariance.pose.orientation.x = 0.0; + input_objects[2].kinematics.pose_with_covariance.pose.orientation.y = 0.0; + input_objects[2].kinematics.pose_with_covariance.pose.orientation.z = 0.0; + input_objects[2].kinematics.pose_with_covariance.pose.orientation.w = 1.0; + input_objects[2].shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; + input_objects[2].shape.dimensions.x = 4.0; + input_objects[2].shape.dimensions.y = 2.0; + + // Object 4 (different class) + autoware_auto_perception_msgs::msg::ObjectClassification obj4_classification; + obj4_classification.label = 1; // Assuming "pedestrian" has label 1 + obj4_classification.probability = 1.0; + input_objects[3].classification = {obj4_classification}; // Assuming "pedestrian" has label 1 + input_objects[3].kinematics.pose_with_covariance.pose.position.x = 0.0; + input_objects[3].kinematics.pose_with_covariance.pose.position.y = 0.0; + input_objects[3].kinematics.pose_with_covariance.pose.orientation.x = 0.0; + input_objects[3].kinematics.pose_with_covariance.pose.orientation.y = 0.0; + input_objects[3].kinematics.pose_with_covariance.pose.orientation.z = 0.0; + input_objects[3].kinematics.pose_with_covariance.pose.orientation.w = 1.0; + input_objects[3].shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; + input_objects[3].shape.dimensions.x = 0.5; + input_objects[3].shape.dimensions.y = 0.5; + + std::vector output_objects = nms.apply(input_objects); + + // Assert the expected number of output objects + EXPECT_EQ(output_objects.size(), 3); + + // Assert that input_objects[2] is included in the output_objects + bool is_input_object_2_included = false; + for (const auto & output_object : output_objects) { + if (output_object == input_objects[2]) { + is_input_object_2_included = true; + break; + } + } + EXPECT_TRUE(is_input_object_2_included); + + // Assert that input_objects[3] is included in the output_objects + bool is_input_object_3_included = false; + for (const auto & output_object : output_objects) { + if (output_object == input_objects[3]) { + is_input_object_3_included = true; + break; + } + } + EXPECT_TRUE(is_input_object_3_included); +} + +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/perception/lidar_centerpoint/test/test_postprocess_kernel.cpp b/perception/lidar_centerpoint/test/test_postprocess_kernel.cpp new file mode 100644 index 0000000000000..fde4fcbee3d6c --- /dev/null +++ b/perception/lidar_centerpoint/test/test_postprocess_kernel.cpp @@ -0,0 +1,367 @@ +// 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 "test_postprocess_kernel.hpp" + +#include + +#include +#include +#include + +namespace centerpoint +{ + +void PostprocessKernelTest::SetUp() +{ + cudaStreamCreate(&stream_); + + constexpr std::size_t class_size{5}; + constexpr std::size_t point_feature_size{4}; + constexpr std::size_t max_voxel_size{100000000}; + const std::vector point_cloud_range{-76.8, -76.8, -4.0, 76.8, 76.8, 6.0}; + const std::vector voxel_size{0.32, 0.32, 10.0}; + constexpr std::size_t downsample_factor{1}; + constexpr std::size_t encoder_in_feature_size{9}; + constexpr float score_threshold{0.35f}; + constexpr float circle_nms_dist_threshold{0.5f}; + const std::vector yaw_norm_thresholds{0.5, 0.5, 0.5}; + constexpr bool has_variance{false}; + + config_ptr_ = std::make_unique( + class_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, has_variance); + + postprocess_cuda_ptr_ = std::make_unique(*config_ptr_); + + const auto grid_xy_size = config_ptr_->down_grid_size_x_ * config_ptr_->down_grid_size_y_; + + head_out_heatmap_d_ = cuda::make_unique(grid_xy_size * config_ptr_->class_size_); + head_out_offset_d_ = + cuda::make_unique(grid_xy_size * config_ptr_->head_out_offset_size_); + head_out_z_d_ = cuda::make_unique(grid_xy_size * config_ptr_->head_out_z_size_); + head_out_dim_d_ = cuda::make_unique(grid_xy_size * config_ptr_->head_out_dim_size_); + head_out_rot_d_ = cuda::make_unique(grid_xy_size * config_ptr_->head_out_rot_size_); + head_out_vel_d_ = cuda::make_unique(grid_xy_size * config_ptr_->head_out_vel_size_); + + std::vector heatmap_host_vector(grid_xy_size * config_ptr_->class_size_, 0.f); + std::fill(heatmap_host_vector.begin(), heatmap_host_vector.end(), -1e6); + cudaMemcpy( + head_out_heatmap_d_.get(), heatmap_host_vector.data(), + grid_xy_size * config_ptr_->head_out_offset_size_ * sizeof(float), cudaMemcpyHostToDevice); + cudaMemset( + head_out_offset_d_.get(), 0, grid_xy_size * config_ptr_->head_out_offset_size_ * sizeof(float)); + cudaMemset(head_out_z_d_.get(), 0, grid_xy_size * config_ptr_->head_out_z_size_ * sizeof(float)); + cudaMemset( + head_out_dim_d_.get(), 0, grid_xy_size * config_ptr_->head_out_dim_size_ * sizeof(float)); + cudaMemset( + head_out_rot_d_.get(), 0, grid_xy_size * config_ptr_->head_out_rot_size_ * sizeof(float)); + cudaMemset( + head_out_vel_d_.get(), 0, grid_xy_size * config_ptr_->head_out_vel_size_ * sizeof(float)); +} + +void PostprocessKernelTest::TearDown() +{ +} + +TEST_F(PostprocessKernelTest, EmptyTensorTest) +{ + std::vector det_boxes3d; + + postprocess_cuda_ptr_->generateDetectedBoxes3D_launch( + head_out_heatmap_d_.get(), head_out_offset_d_.get(), head_out_z_d_.get(), head_out_dim_d_.get(), + head_out_rot_d_.get(), head_out_vel_d_.get(), det_boxes3d, stream_); + + ASSERT_EQ(0, det_boxes3d.size()); +} + +TEST_F(PostprocessKernelTest, SingleDetectionTest) +{ + std::vector det_boxes3d; + + constexpr float detection_x = 70.f; + constexpr float detection_y = -38.4f; + constexpr float detection_z = 1.0; + constexpr float detection_log_w = std::log(7.0); + constexpr float detection_log_l = std::log(1.0); + constexpr float detection_log_h = std::log(2.0); + constexpr float detection_yaw = M_PI_4; + constexpr float detection_yaw_sin = std::sin(detection_yaw); + constexpr float detection_yaw_cos = std::sin(detection_yaw); + constexpr float detection_vel_x = 5.0; + constexpr float detection_vel_y = -5.0; + + const float idx = + ((detection_x - config_ptr_->range_min_x_) / + (config_ptr_->voxel_size_x_ * config_ptr_->downsample_factor_)); + const float idy = + ((detection_y - config_ptr_->range_min_y_) / + (config_ptr_->voxel_size_y_ * config_ptr_->downsample_factor_)); + const std::size_t index = config_ptr_->down_grid_size_x_ * std::floor(idy) + std::floor(idx); + const float detection_x_offset = idx - std::floor(idx); + const float detection_y_offset = idy - std::floor(idy); + + // Set the values in the cuda tensor + const auto grid_xy_size = config_ptr_->down_grid_size_x_ * config_ptr_->down_grid_size_y_; + float score = 1.f; + cudaMemcpy( + &head_out_heatmap_d_[2 * grid_xy_size + index], &score, 1 * sizeof(float), + cudaMemcpyHostToDevice); + + cudaMemcpy( + &head_out_offset_d_[0 * grid_xy_size + index], &detection_x_offset, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &head_out_offset_d_[1 * grid_xy_size + index], &detection_y_offset, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &head_out_z_d_[0 * grid_xy_size + index], &detection_z, 1 * sizeof(float), + cudaMemcpyHostToDevice); + + cudaMemcpy( + &head_out_dim_d_[0 * grid_xy_size + index], &detection_log_w, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &head_out_dim_d_[1 * grid_xy_size + index], &detection_log_l, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &head_out_dim_d_[2 * grid_xy_size + index], &detection_log_h, 1 * sizeof(float), + cudaMemcpyHostToDevice); + + cudaMemcpy( + &head_out_rot_d_[0 * grid_xy_size + index], &detection_yaw_cos, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &head_out_rot_d_[1 * grid_xy_size + index], &detection_yaw_sin, 1 * sizeof(float), + cudaMemcpyHostToDevice); + + cudaMemcpy( + &head_out_vel_d_[0 * grid_xy_size + index], &detection_vel_x, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &head_out_vel_d_[1 * grid_xy_size + index], &detection_vel_y, 1 * sizeof(float), + cudaMemcpyHostToDevice); + + auto code = cudaGetLastError(); + ASSERT_EQ(cudaSuccess, code); + + // Extract the boxes + code = postprocess_cuda_ptr_->generateDetectedBoxes3D_launch( + head_out_heatmap_d_.get(), head_out_offset_d_.get(), head_out_z_d_.get(), head_out_dim_d_.get(), + head_out_rot_d_.get(), head_out_vel_d_.get(), det_boxes3d, stream_); + + ASSERT_EQ(cudaSuccess, code); + ASSERT_EQ(1, det_boxes3d.size()); + + const auto det_box3d = det_boxes3d[0]; + EXPECT_EQ(detection_x, det_box3d.x); + EXPECT_EQ(detection_y, det_box3d.y); + EXPECT_EQ(detection_z, det_box3d.z); + EXPECT_NEAR(std::exp(detection_log_w), det_box3d.width, 1e-6); + EXPECT_NEAR(std::exp(detection_log_l), det_box3d.length, 1e-6); + EXPECT_NEAR(std::exp(detection_log_h), det_box3d.height, 1e-6); + EXPECT_EQ(detection_yaw, det_box3d.yaw); + EXPECT_EQ(detection_vel_x, det_box3d.vel_x); + EXPECT_EQ(detection_vel_y, det_box3d.vel_y); +} + +TEST_F(PostprocessKernelTest, InvalidYawTest) +{ + std::vector det_boxes3d; + + constexpr float detection_x = 70.f; + constexpr float detection_y = -38.4f; + constexpr float detection_z = 1.0; + constexpr float detection_yaw_sin = 0.0; + constexpr float detection_yaw_cos = 0.2; + + const float idx = + ((detection_x - config_ptr_->range_min_x_) / + (config_ptr_->voxel_size_x_ * config_ptr_->downsample_factor_)); + const float idy = + ((detection_y - config_ptr_->range_min_y_) / + (config_ptr_->voxel_size_y_ * config_ptr_->downsample_factor_)); + const std::size_t index = config_ptr_->down_grid_size_x_ * std::floor(idy) + std::floor(idx); + const float detection_x_offset = idx - std::floor(idx); + const float detection_y_offset = idy - std::floor(idy); + + // Set the values in the cuda tensor + const auto grid_xy_size = config_ptr_->down_grid_size_x_ * config_ptr_->down_grid_size_y_; + float score = 1.f; + cudaMemcpy( + &head_out_heatmap_d_[2 * grid_xy_size + index], &score, 1 * sizeof(float), + cudaMemcpyHostToDevice); + + cudaMemcpy( + &head_out_offset_d_[0 * grid_xy_size + index], &detection_x_offset, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &head_out_offset_d_[1 * grid_xy_size + index], &detection_y_offset, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &head_out_z_d_[0 * grid_xy_size + index], &detection_z, 1 * sizeof(float), + cudaMemcpyHostToDevice); + + cudaMemcpy( + &head_out_rot_d_[0 * grid_xy_size + index], &detection_yaw_cos, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &head_out_rot_d_[1 * grid_xy_size + index], &detection_yaw_sin, 1 * sizeof(float), + cudaMemcpyHostToDevice); + + auto code = cudaGetLastError(); + ASSERT_EQ(cudaSuccess, code); + + // Extract the boxes + code = postprocess_cuda_ptr_->generateDetectedBoxes3D_launch( + head_out_heatmap_d_.get(), head_out_offset_d_.get(), head_out_z_d_.get(), head_out_dim_d_.get(), + head_out_rot_d_.get(), head_out_vel_d_.get(), det_boxes3d, stream_); + + ASSERT_EQ(cudaSuccess, code); + ASSERT_EQ(0, det_boxes3d.size()); +} + +TEST_F(PostprocessKernelTest, CircleNMSTest) +{ + std::vector det_boxes3d; + + constexpr float detection_x = 70.f; + constexpr float detection_y = -38.4f; + constexpr float detection_z = 1.0; + constexpr float detection_log_w = std::log(7.0); + constexpr float detection_log_l = std::log(1.0); + constexpr float detection_log_h = std::log(2.0); + constexpr float detection_yaw1_sin = 0.0; + constexpr float detection_yaw1_cos = 1.0; + constexpr float detection_yaw2_sin = 1.0; + constexpr float detection_yaw2_cos = 0.0; + constexpr float detection_vel_x = 5.0; + constexpr float detection_vel_y = -5.0; + + const float idx1 = + ((detection_x - config_ptr_->range_min_x_) / + (config_ptr_->voxel_size_x_ * config_ptr_->downsample_factor_)); + const float idy1 = + ((detection_y - config_ptr_->range_min_y_) / + (config_ptr_->voxel_size_y_ * config_ptr_->downsample_factor_)); + const std::size_t index1 = config_ptr_->down_grid_size_x_ * std::floor(idy1) + std::floor(idx1); + const float detection_x_offset1 = idx1 - std::floor(idx1); + const float detection_y_offset1 = idy1 - std::floor(idy1); + + const float idx2 = idx1 + 1.0; + const float idy2 = idy1 + 1.0; + const std::size_t index2 = config_ptr_->down_grid_size_x_ * std::floor(idy2) + std::floor(idx2); + const float detection_x_offset2 = detection_x_offset1 - 1.0; + const float detection_y_offset2 = detection_y_offset1 - 1.0; + + // Set the values in the cuda tensor + const auto grid_xy_size = config_ptr_->down_grid_size_x_ * config_ptr_->down_grid_size_y_; + float score = 1.f; + + cudaMemcpy( + &head_out_heatmap_d_[2 * grid_xy_size + index1], &score, 1 * sizeof(float), + cudaMemcpyHostToDevice); + + cudaMemcpy( + &head_out_offset_d_[0 * grid_xy_size + index1], &detection_x_offset1, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &head_out_offset_d_[1 * grid_xy_size + index1], &detection_y_offset1, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &head_out_z_d_[0 * grid_xy_size + index1], &detection_z, 1 * sizeof(float), + cudaMemcpyHostToDevice); + + cudaMemcpy( + &head_out_dim_d_[0 * grid_xy_size + index1], &detection_log_w, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &head_out_dim_d_[1 * grid_xy_size + index1], &detection_log_l, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &head_out_dim_d_[2 * grid_xy_size + index1], &detection_log_h, 1 * sizeof(float), + cudaMemcpyHostToDevice); + + cudaMemcpy( + &head_out_rot_d_[0 * grid_xy_size + index1], &detection_yaw1_cos, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &head_out_rot_d_[1 * grid_xy_size + index1], &detection_yaw1_sin, 1 * sizeof(float), + cudaMemcpyHostToDevice); + + cudaMemcpy( + &head_out_vel_d_[0 * grid_xy_size + index1], &detection_vel_x, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &head_out_vel_d_[1 * grid_xy_size + index1], &detection_vel_y, 1 * sizeof(float), + cudaMemcpyHostToDevice); + + cudaMemcpy( + &head_out_heatmap_d_[2 * grid_xy_size + index2], &score, 1 * sizeof(float), + cudaMemcpyHostToDevice); + + cudaMemcpy( + &head_out_offset_d_[0 * grid_xy_size + index2], &detection_x_offset2, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &head_out_offset_d_[1 * grid_xy_size + index2], &detection_y_offset2, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &head_out_z_d_[0 * grid_xy_size + index2], &detection_z, 1 * sizeof(float), + cudaMemcpyHostToDevice); + + cudaMemcpy( + &head_out_dim_d_[0 * grid_xy_size + index2], &detection_log_w, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &head_out_dim_d_[1 * grid_xy_size + index2], &detection_log_l, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &head_out_dim_d_[2 * grid_xy_size + index2], &detection_log_h, 1 * sizeof(float), + cudaMemcpyHostToDevice); + + cudaMemcpy( + &head_out_rot_d_[0 * grid_xy_size + index2], &detection_yaw2_cos, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &head_out_rot_d_[1 * grid_xy_size + index2], &detection_yaw2_sin, 1 * sizeof(float), + cudaMemcpyHostToDevice); + + cudaMemcpy( + &head_out_vel_d_[0 * grid_xy_size + index2], &detection_vel_x, 1 * sizeof(float), + cudaMemcpyHostToDevice); + cudaMemcpy( + &head_out_vel_d_[1 * grid_xy_size + index2], &detection_vel_y, 1 * sizeof(float), + cudaMemcpyHostToDevice); + + auto code = cudaGetLastError(); + ASSERT_EQ(cudaSuccess, code); + + // Extract the boxes + code = postprocess_cuda_ptr_->generateDetectedBoxes3D_launch( + head_out_heatmap_d_.get(), head_out_offset_d_.get(), head_out_z_d_.get(), head_out_dim_d_.get(), + head_out_rot_d_.get(), head_out_vel_d_.get(), det_boxes3d, stream_); + + ASSERT_EQ(cudaSuccess, code); + ASSERT_EQ(1, det_boxes3d.size()); +} + +} // namespace centerpoint + +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/perception/lidar_centerpoint/test/test_postprocess_kernel.hpp b/perception/lidar_centerpoint/test/test_postprocess_kernel.hpp new file mode 100644 index 0000000000000..d0c9123da9e77 --- /dev/null +++ b/perception/lidar_centerpoint/test/test_postprocess_kernel.hpp @@ -0,0 +1,49 @@ +// 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 TEST_POSTPROCESS_KERNEL_HPP_ +#define TEST_POSTPROCESS_KERNEL_HPP_ + +#include +#include + +#include + +#include + +namespace centerpoint +{ + +class PostprocessKernelTest : public testing::Test +{ +public: + void SetUp() override; + void TearDown() override; + + cudaStream_t stream_{nullptr}; + + std::unique_ptr postprocess_cuda_ptr_; + std::unique_ptr config_ptr_; + + cuda::unique_ptr head_out_heatmap_d_; + cuda::unique_ptr head_out_offset_d_; + cuda::unique_ptr head_out_z_d_; + cuda::unique_ptr head_out_dim_d_; + cuda::unique_ptr head_out_rot_d_; + cuda::unique_ptr head_out_vel_d_; +}; + +} // namespace centerpoint + +#endif // TEST_POSTPROCESS_KERNEL_HPP_ diff --git a/perception/lidar_centerpoint/test/test_preprocess_kernel.cpp b/perception/lidar_centerpoint/test/test_preprocess_kernel.cpp new file mode 100644 index 0000000000000..db75328f9d5c5 --- /dev/null +++ b/perception/lidar_centerpoint/test/test_preprocess_kernel.cpp @@ -0,0 +1,403 @@ +// 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 "test_preprocess_kernel.hpp" + +#include + +#include +#include +#include + +#include +#include +#include + +namespace centerpoint +{ + +void PreprocessKernelTest::SetUp() +{ + cudaStreamCreate(&stream_); + + max_voxel_size_ = 40000; + max_point_in_voxel_size_ = + 32; // this value is actually hardcoded in the kernel so it can not be changed + point_feature_size_ = 4; + point_dim_size_ = 3; + config_encoder_in_feature_size_ = 9; + encoder_out_feature_size_ = 32; + capacity_ = 1000000; + + range_min_x_ = -76.8f; + range_min_y_ = -76.8f; + range_min_z_ = -4.0f; + range_max_x_ = 76.8f; + range_max_y_ = 76.8f; + range_max_z_ = 6.0f; + voxel_size_x_ = 0.32f; + voxel_size_y_ = 0.32f; + voxel_size_z_ = 10.0f; + + grid_size_x_ = static_cast((range_max_x_ - range_min_x_) / voxel_size_x_); + grid_size_y_ = static_cast((range_max_y_ - range_min_y_) / voxel_size_y_); + grid_size_z_ = static_cast((range_max_z_ - range_min_z_) / voxel_size_z_); + + voxels_size_ = max_voxel_size_ * max_point_in_voxel_size_ * point_feature_size_; + coordinates_size_ = max_voxel_size_ * point_dim_size_; + encoder_in_feature_size_ = + max_voxel_size_ * max_point_in_voxel_size_ * config_encoder_in_feature_size_; + pillar_features_size_ = max_voxel_size_ * encoder_out_feature_size_; + spatial_features_size_ = grid_size_x_ * grid_size_y_ * encoder_out_feature_size_; + grid_xy_size_ = grid_size_x_ * grid_size_y_; + + voxels_buffer_size_ = + grid_size_x_ * grid_size_y_ * max_point_in_voxel_size_ * point_feature_size_; + mask_size_ = grid_size_x_ * grid_size_y_; + + voxels_d_ = cuda::make_unique(voxels_size_); + coordinates_d_ = cuda::make_unique(coordinates_size_); + num_points_per_voxel_d_ = cuda::make_unique(max_voxel_size_); + encoder_in_features_d_ = cuda::make_unique(encoder_in_feature_size_); + pillar_features_d_ = cuda::make_unique(pillar_features_size_); + spatial_features_d_ = cuda::make_unique(spatial_features_size_); + points_d_ = cuda::make_unique(capacity_ * point_feature_size_); + voxels_buffer_d_ = cuda::make_unique(voxels_buffer_size_); + mask_d_ = cuda::make_unique(mask_size_); + num_voxels_d_ = cuda::make_unique(1); + + CHECK_CUDA_ERROR(cudaMemsetAsync(num_voxels_d_.get(), 0, sizeof(unsigned int), stream_)); + CHECK_CUDA_ERROR( + cudaMemsetAsync(voxels_buffer_d_.get(), 0, voxels_buffer_size_ * sizeof(float), stream_)); + CHECK_CUDA_ERROR(cudaMemsetAsync(mask_d_.get(), 0, mask_size_ * sizeof(int), stream_)); + CHECK_CUDA_ERROR(cudaMemsetAsync(voxels_d_.get(), 0, voxels_size_ * sizeof(float), stream_)); + CHECK_CUDA_ERROR( + cudaMemsetAsync(coordinates_d_.get(), 0, coordinates_size_ * sizeof(int), stream_)); + CHECK_CUDA_ERROR( + cudaMemsetAsync(num_points_per_voxel_d_.get(), 0, max_voxel_size_ * sizeof(float), stream_)); +} + +void PreprocessKernelTest::TearDown() +{ +} + +TEST_F(PreprocessKernelTest, EmptyVoxelTest) +{ + std::vector points{}; + std::size_t points_num = 0; + + CHECK_CUDA_ERROR(cudaMemcpy( + points_d_.get(), points.data(), points_num * point_feature_size_ * sizeof(float), + cudaMemcpyHostToDevice)); + + cudaError_t code = centerpoint::generateVoxels_random_launch( + points_d_.get(), points_num, range_min_x_, range_max_x_, range_min_y_, range_max_y_, + range_min_z_, range_max_z_, voxel_size_x_, voxel_size_y_, voxel_size_z_, grid_size_y_, + grid_size_x_, mask_d_.get(), voxels_buffer_d_.get(), stream_); + + ASSERT_EQ(cudaSuccess, code); + + // Compute the total amount of voxels filled + thrust::host_vector mask_h(mask_size_); + + CHECK_CUDA_ERROR(cudaMemcpy( + mask_h.data(), mask_d_.get(), mask_size_ * sizeof(unsigned int), cudaMemcpyDeviceToHost)); + + int sum = thrust::reduce(mask_h.begin(), mask_h.end(), 0); + EXPECT_EQ(0, sum); +} + +TEST_F(PreprocessKernelTest, BasicTest) +{ + std::vector points{25.f, -61.1f, 1.8f, 0.1f}; + std::size_t points_num = 1; + + CHECK_CUDA_ERROR(cudaMemcpy( + points_d_.get(), points.data(), points_num * point_feature_size_ * sizeof(float), + cudaMemcpyHostToDevice)); + + cudaError_t code = centerpoint::generateVoxels_random_launch( + points_d_.get(), points_num, range_min_x_, range_max_x_, range_min_y_, range_max_y_, + range_min_z_, range_max_z_, voxel_size_x_, voxel_size_y_, voxel_size_z_, grid_size_y_, + grid_size_x_, mask_d_.get(), voxels_buffer_d_.get(), stream_); + + ASSERT_EQ(cudaSuccess, code); + + // Compute the total amount of voxels filled + thrust::host_vector mask_h(mask_size_); + + CHECK_CUDA_ERROR(cudaMemcpy( + mask_h.data(), mask_d_.get(), mask_size_ * sizeof(unsigned int), cudaMemcpyDeviceToHost)); + + int sum = thrust::reduce(mask_h.begin(), mask_h.end(), 0); + EXPECT_EQ(1, sum); + + // Check that the voxel was filled + int voxel_idx = std::floor((points[0] - range_min_x_) / voxel_size_x_); + int voxel_idy = std::floor((points[1] - range_min_y_) / voxel_size_y_); + unsigned int voxel_index = voxel_idy * grid_size_x_ + voxel_idx; + + unsigned voxel_count; + std::array voxel_data{0.f, 0.f, 0.f, 0.f}; + + CHECK_CUDA_ERROR(cudaMemcpy( + &voxel_count, mask_d_.get() + voxel_index, 1 * sizeof(unsigned int), cudaMemcpyDeviceToHost)); + + EXPECT_EQ(1, voxel_count); + + CHECK_CUDA_ERROR(cudaMemcpy( + voxel_data.data(), + voxels_buffer_d_.get() + voxel_index * max_point_in_voxel_size_ * point_feature_size_, + point_feature_size_ * sizeof(unsigned int), cudaMemcpyDeviceToHost)); + + EXPECT_EQ(points[0], voxel_data[0]); + EXPECT_EQ(points[1], voxel_data[1]); + EXPECT_EQ(points[2], voxel_data[2]); + EXPECT_EQ(points[3], voxel_data[3]); + + code = generateBaseFeatures_launch( + mask_d_.get(), voxels_buffer_d_.get(), grid_size_y_, grid_size_x_, max_voxel_size_, + num_voxels_d_.get(), voxels_d_.get(), num_points_per_voxel_d_.get(), coordinates_d_.get(), + stream_); + + ASSERT_EQ(cudaSuccess, code); + + unsigned int num_pillars{}; + std::vector voxel_features(point_feature_size_, 0.f); + float num_voxels{}; + std::vector voxel_coordinates(3, 0); + + CHECK_CUDA_ERROR(cudaMemcpy( + &num_pillars, num_voxels_d_.get(), 1 * sizeof(unsigned int), cudaMemcpyDeviceToHost)); + + CHECK_CUDA_ERROR(cudaMemcpy( + voxel_features.data(), voxels_d_.get(), point_feature_size_ * sizeof(unsigned int), + cudaMemcpyDeviceToHost)); + + CHECK_CUDA_ERROR(cudaMemcpy( + &num_voxels, num_points_per_voxel_d_.get(), 1 * sizeof(float), cudaMemcpyDeviceToHost)); + + CHECK_CUDA_ERROR(cudaMemcpy( + voxel_coordinates.data(), coordinates_d_.get(), 3 * sizeof(int), cudaMemcpyDeviceToHost)); + + EXPECT_EQ(1, num_pillars); + EXPECT_EQ(1.0, num_voxels); + EXPECT_EQ(0, voxel_coordinates[0]); + EXPECT_EQ(voxel_idy, voxel_coordinates[1]); + EXPECT_EQ(voxel_idx, voxel_coordinates[2]); + EXPECT_EQ(points[0], voxel_features[0]); + EXPECT_EQ(points[1], voxel_features[1]); + EXPECT_EQ(points[2], voxel_features[2]); + EXPECT_EQ(points[3], voxel_features[3]); + + code = generateFeatures_launch( + voxels_d_.get(), num_points_per_voxel_d_.get(), coordinates_d_.get(), num_voxels_d_.get(), + max_voxel_size_, voxel_size_x_, voxel_size_y_, voxel_size_z_, range_min_x_, range_min_y_, + range_min_z_, encoder_in_features_d_.get(), stream_); + + ASSERT_EQ(cudaSuccess, code); + + std::vector encoder_features(config_encoder_in_feature_size_, 0.f); + + CHECK_CUDA_ERROR(cudaMemcpy( + encoder_features.data(), encoder_in_features_d_.get(), + config_encoder_in_feature_size_ * sizeof(float), cudaMemcpyDeviceToHost)); + + // The first four values are just the point features + EXPECT_EQ(points[0], encoder_features[0]); + EXPECT_EQ(points[1], encoder_features[1]); + EXPECT_EQ(points[2], encoder_features[2]); + EXPECT_EQ(points[3], encoder_features[3]); + + // The next three values are the relative coordinates with respect to the voxel average + EXPECT_EQ(0.0, encoder_features[4]); + EXPECT_EQ(0.0, encoder_features[5]); + EXPECT_EQ(0.0, encoder_features[6]); + + // The last two values are the relative coordinates with respect to the voxel center + float voxel_x_offset = voxel_size_x_ / 2 + voxel_idx * voxel_size_x_ + range_min_x_; + float voxel_y_offset = voxel_size_y_ / 2 + voxel_idy * voxel_size_y_ + range_min_y_; + + EXPECT_EQ(points[0] - voxel_x_offset, encoder_features[7]); + EXPECT_EQ(points[1] - voxel_y_offset, encoder_features[8]); +} + +TEST_F(PreprocessKernelTest, OutOfRangeTest) +{ + std::vector points{25.f, -61.1f, 100.f, 0.1f}; // 100.f is out of range + std::size_t points_num = 1; + + CHECK_CUDA_ERROR(cudaMemcpy( + points_d_.get(), points.data(), points_num * point_feature_size_ * sizeof(float), + cudaMemcpyHostToDevice)); + + cudaError_t code = centerpoint::generateVoxels_random_launch( + points_d_.get(), points_num, range_min_x_, range_max_x_, range_min_y_, range_max_y_, + range_min_z_, range_max_z_, voxel_size_x_, voxel_size_y_, voxel_size_z_, grid_size_y_, + grid_size_x_, mask_d_.get(), voxels_buffer_d_.get(), stream_); + + ASSERT_EQ(cudaSuccess, code); + + // Compute the total amount of voxels filled + thrust::host_vector mask_h(mask_size_); + + CHECK_CUDA_ERROR(cudaMemcpy( + mask_h.data(), mask_d_.get(), mask_size_ * sizeof(unsigned int), cudaMemcpyDeviceToHost)); + + int sum = thrust::reduce(mask_h.begin(), mask_h.end(), 0); + EXPECT_EQ(0, sum); +} + +TEST_F(PreprocessKernelTest, VoxelOverflowTest) +{ + std::array point{25.f, -61.1f, 1.8f, 0.1f}; + std::size_t points_num = 64; + std::vector points{}; + + for (std::size_t i = 0; i < points_num; ++i) { + points.insert(points.end(), point.begin(), point.end()); + } + + CHECK_CUDA_ERROR(cudaMemcpy( + points_d_.get(), points.data(), points_num * point_feature_size_ * sizeof(float), + cudaMemcpyHostToDevice)); + + // Note: due to atomic operations in the kernel, generateVoxels does not handle overflows in the + // counter, and instead is done in the following kernel + cudaError_t code = centerpoint::generateVoxels_random_launch( + points_d_.get(), points_num, range_min_x_, range_max_x_, range_min_y_, range_max_y_, + range_min_z_, range_max_z_, voxel_size_x_, voxel_size_y_, voxel_size_z_, grid_size_y_, + grid_size_x_, mask_d_.get(), voxels_buffer_d_.get(), stream_); + + ASSERT_EQ(cudaSuccess, code); + + // Check that the voxel was filled + int voxel_idx = std::floor((points[0] - range_min_x_) / voxel_size_x_); + int voxel_idy = std::floor((points[1] - range_min_y_) / voxel_size_y_); + unsigned int voxel_index = voxel_idy * grid_size_x_ + voxel_idx; + + std::vector voxel_data{}; + voxel_data.resize((max_point_in_voxel_size_ + 1) * point_feature_size_); + + CHECK_CUDA_ERROR(cudaMemcpy( + voxel_data.data(), + voxels_buffer_d_.get() + voxel_index * max_point_in_voxel_size_ * point_feature_size_, + (max_point_in_voxel_size_ + 1) * point_feature_size_ * sizeof(unsigned int), + cudaMemcpyDeviceToHost)); + + for (std::size_t i = 0; i < max_point_in_voxel_size_; ++i) { + EXPECT_EQ(points[0], voxel_data[i * point_feature_size_ + 0]); + EXPECT_EQ(points[1], voxel_data[i * point_feature_size_ + 1]); + EXPECT_EQ(points[2], voxel_data[i * point_feature_size_ + 2]); + EXPECT_EQ(points[3], voxel_data[i * point_feature_size_ + 3]); + } + + EXPECT_EQ(0.0, voxel_data[max_point_in_voxel_size_ * point_feature_size_ + 0]); + EXPECT_EQ(0.0, voxel_data[max_point_in_voxel_size_ * point_feature_size_ + 1]); + EXPECT_EQ(0.0, voxel_data[max_point_in_voxel_size_ * point_feature_size_ + 2]); + EXPECT_EQ(0.0, voxel_data[max_point_in_voxel_size_ * point_feature_size_ + 3]); + + code = generateBaseFeatures_launch( + mask_d_.get(), voxels_buffer_d_.get(), grid_size_y_, grid_size_x_, max_voxel_size_, + num_voxels_d_.get(), voxels_d_.get(), num_points_per_voxel_d_.get(), coordinates_d_.get(), + stream_); + + ASSERT_EQ(cudaSuccess, code); + + unsigned int num_pillars{}; + std::vector voxel_features(max_point_in_voxel_size_ * point_feature_size_, 0.f); + float num_voxels{}; + std::vector voxel_coordinates(3, 0); + + CHECK_CUDA_ERROR(cudaMemcpy( + &num_pillars, num_voxels_d_.get(), 1 * sizeof(unsigned int), cudaMemcpyDeviceToHost)); + + CHECK_CUDA_ERROR(cudaMemcpy( + voxel_features.data(), voxels_d_.get(), + max_point_in_voxel_size_ * point_feature_size_ * sizeof(unsigned int), cudaMemcpyDeviceToHost)); + + CHECK_CUDA_ERROR(cudaMemcpy( + &num_voxels, num_points_per_voxel_d_.get(), 1 * sizeof(float), cudaMemcpyDeviceToHost)); + + CHECK_CUDA_ERROR(cudaMemcpy( + voxel_coordinates.data(), coordinates_d_.get(), 3 * sizeof(int), cudaMemcpyDeviceToHost)); + + EXPECT_EQ(1, num_pillars); + EXPECT_EQ(static_cast(max_point_in_voxel_size_), num_voxels); + EXPECT_EQ(0, voxel_coordinates[0]); + EXPECT_EQ(voxel_idy, voxel_coordinates[1]); + EXPECT_EQ(voxel_idx, voxel_coordinates[2]); + + for (std::size_t point_index = 0; point_index < max_point_in_voxel_size_; ++point_index) { + EXPECT_EQ(points[0], voxel_features[point_index * point_feature_size_ + 0]); + EXPECT_EQ(points[1], voxel_features[point_index * point_feature_size_ + 1]); + EXPECT_EQ(points[2], voxel_features[point_index * point_feature_size_ + 2]); + EXPECT_EQ(points[3], voxel_features[point_index * point_feature_size_ + 3]); + } + + code = generateFeatures_launch( + voxels_d_.get(), num_points_per_voxel_d_.get(), coordinates_d_.get(), num_voxels_d_.get(), + max_voxel_size_, voxel_size_x_, voxel_size_y_, voxel_size_z_, range_min_x_, range_min_y_, + range_min_z_, encoder_in_features_d_.get(), stream_); + + ASSERT_EQ(cudaSuccess, code); + + std::vector encoder_features( + max_point_in_voxel_size_ * config_encoder_in_feature_size_, 0.f); + + CHECK_CUDA_ERROR(cudaMemcpy( + encoder_features.data(), encoder_in_features_d_.get(), + max_point_in_voxel_size_ * config_encoder_in_feature_size_ * sizeof(float), + cudaMemcpyDeviceToHost)); + + float voxel_x_offset = voxel_size_x_ / 2 + voxel_idx * voxel_size_x_ + range_min_x_; + float voxel_y_offset = voxel_size_y_ / 2 + voxel_idy * voxel_size_y_ + range_min_y_; + + for (std::size_t point_index = 0; point_index < max_point_in_voxel_size_; ++point_index) { + // The first four values are just the point features + EXPECT_EQ( + points[point_index * point_feature_size_ + 0], + encoder_features[point_index * config_encoder_in_feature_size_ + 0]); + EXPECT_EQ( + points[point_index * point_feature_size_ + 1], + encoder_features[point_index * config_encoder_in_feature_size_ + 1]); + EXPECT_EQ( + points[point_index * point_feature_size_ + 2], + encoder_features[point_index * config_encoder_in_feature_size_ + 2]); + EXPECT_EQ( + points[point_index * point_feature_size_ + 3], + encoder_features[point_index * config_encoder_in_feature_size_ + 3]); + + // The next three values are the relative coordinates with respect to the voxel average + EXPECT_NEAR(0.0, encoder_features[point_index * config_encoder_in_feature_size_ + 4], 1e-4); + EXPECT_NEAR(0.0, encoder_features[point_index * config_encoder_in_feature_size_ + 5], 1e-4); + EXPECT_NEAR(0.0, encoder_features[point_index * config_encoder_in_feature_size_ + 6], 1e-4); + + // The last two values are the relative coordinates with respect to the voxel center + EXPECT_EQ( + points[point_index * point_feature_size_ + 0] - voxel_x_offset, + encoder_features[point_index * config_encoder_in_feature_size_ + 7]); + EXPECT_EQ( + points[point_index * point_feature_size_ + 1] - voxel_y_offset, + encoder_features[point_index * config_encoder_in_feature_size_ + 8]); + } +} + +} // namespace centerpoint + +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/perception/lidar_centerpoint/test/test_preprocess_kernel.hpp b/perception/lidar_centerpoint/test/test_preprocess_kernel.hpp new file mode 100644 index 0000000000000..57ff51966a417 --- /dev/null +++ b/perception/lidar_centerpoint/test/test_preprocess_kernel.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 TEST_PREPROCESS_KERNEL_HPP_ +#define TEST_PREPROCESS_KERNEL_HPP_ + +#include + +#include + +namespace centerpoint +{ + +class PreprocessKernelTest : public testing::Test +{ +public: + void SetUp() override; + void TearDown() override; + + cudaStream_t stream_{nullptr}; + + std::size_t max_voxel_size_{}; + std::size_t max_point_in_voxel_size_{}; + std::size_t point_feature_size_{}; + std::size_t point_dim_size_{}; + std::size_t config_encoder_in_feature_size_{}; + std::size_t encoder_out_feature_size_{}; + std::size_t capacity_{}; + + float range_min_x_{}; + float range_min_y_{}; + float range_min_z_{}; + float range_max_x_{}; + float range_max_y_{}; + float range_max_z_{}; + float voxel_size_x_{}; + float voxel_size_y_{}; + float voxel_size_z_{}; + + std::size_t grid_size_x_{}; + std::size_t grid_size_y_{}; + std::size_t grid_size_z_{}; + + std::size_t voxels_size_{}; + std::size_t coordinates_size_{}; + std::size_t encoder_in_feature_size_{}; + std::size_t pillar_features_size_{}; + std::size_t spatial_features_size_{}; + std::size_t grid_xy_size_{}; + + std::size_t voxels_buffer_size_{}; + std::size_t mask_size_{}; + + cuda::unique_ptr voxels_d_{}; + cuda::unique_ptr coordinates_d_{}; + cuda::unique_ptr num_points_per_voxel_d_{}; + cuda::unique_ptr encoder_in_features_d_{}; + cuda::unique_ptr pillar_features_d_{}; + cuda::unique_ptr spatial_features_d_{}; + cuda::unique_ptr points_d_{}; + cuda::unique_ptr voxels_buffer_d_{}; + cuda::unique_ptr mask_d_{}; + cuda::unique_ptr num_voxels_d_{}; +}; + +} // namespace centerpoint + +#endif // TEST_PREPROCESS_KERNEL_HPP_ diff --git a/perception/lidar_centerpoint/test/test_ros_utils.cpp b/perception/lidar_centerpoint/test/test_ros_utils.cpp new file mode 100644 index 0000000000000..8d943bac61123 --- /dev/null +++ b/perception/lidar_centerpoint/test/test_ros_utils.cpp @@ -0,0 +1,141 @@ +// 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 "lidar_centerpoint/ros_utils.hpp" + +#include + +TEST(TestSuite, box3DToDetectedObject) +{ + std::vector class_names = {"CAR", "TRUCK", "BUS", "TRAILER", + "BICYCLE", "MOTORBIKE", "PEDESTRIAN"}; + + // Test case 1: Test with valid label, has_twist=true, has_variance=true + { + centerpoint::Box3D box3d; + box3d.score = 0.8f; + box3d.label = 0; // CAR + box3d.x = 1.0; + box3d.y = 2.0; + box3d.z = 3.0; + box3d.yaw = 0.5; + box3d.length = 4.0; + box3d.width = 2.0; + box3d.height = 1.5; + box3d.vel_x = 1.0; + box3d.vel_y = 0.5; + box3d.x_variance = 0.1; + box3d.y_variance = 0.2; + box3d.z_variance = 0.3; + box3d.yaw_variance = 0.4; + box3d.vel_x_variance = 0.5; + box3d.vel_y_variance = 0.6; + + autoware_auto_perception_msgs::msg::DetectedObject obj; + centerpoint::box3DToDetectedObject(box3d, class_names, true, true, obj); + + EXPECT_FLOAT_EQ(obj.existence_probability, 0.8f); + EXPECT_EQ( + obj.classification[0].label, autoware_auto_perception_msgs::msg::ObjectClassification::CAR); + EXPECT_FLOAT_EQ(obj.kinematics.pose_with_covariance.pose.position.x, 1.0); + EXPECT_FLOAT_EQ(obj.kinematics.pose_with_covariance.pose.position.y, 2.0); + EXPECT_FLOAT_EQ(obj.kinematics.pose_with_covariance.pose.position.z, 3.0); + EXPECT_FLOAT_EQ(obj.shape.dimensions.x, 4.0); + EXPECT_FLOAT_EQ(obj.shape.dimensions.y, 2.0); + EXPECT_FLOAT_EQ(obj.shape.dimensions.z, 1.5); + EXPECT_TRUE(obj.kinematics.has_position_covariance); + EXPECT_TRUE(obj.kinematics.has_twist); + EXPECT_TRUE(obj.kinematics.has_twist_covariance); + } + + // Test case 2: Test with invalid label, has_twist=false, has_variance=false + { + centerpoint::Box3D box3d; + box3d.score = 0.5f; + box3d.label = 10; // Invalid + + autoware_auto_perception_msgs::msg::DetectedObject obj; + centerpoint::box3DToDetectedObject(box3d, class_names, false, false, obj); + + EXPECT_FLOAT_EQ(obj.existence_probability, 0.5f); + EXPECT_EQ( + obj.classification[0].label, + autoware_auto_perception_msgs::msg::ObjectClassification::UNKNOWN); + EXPECT_FALSE(obj.kinematics.has_position_covariance); + EXPECT_FALSE(obj.kinematics.has_twist); + EXPECT_FALSE(obj.kinematics.has_twist_covariance); + } +} + +TEST(TestSuite, getSemanticType) +{ + EXPECT_EQ( + centerpoint::getSemanticType("CAR"), + autoware_auto_perception_msgs::msg::ObjectClassification::CAR); + EXPECT_EQ( + centerpoint::getSemanticType("TRUCK"), + autoware_auto_perception_msgs::msg::ObjectClassification::TRUCK); + EXPECT_EQ( + centerpoint::getSemanticType("BUS"), + autoware_auto_perception_msgs::msg::ObjectClassification::BUS); + EXPECT_EQ( + centerpoint::getSemanticType("TRAILER"), + autoware_auto_perception_msgs::msg::ObjectClassification::TRAILER); + EXPECT_EQ( + centerpoint::getSemanticType("BICYCLE"), + autoware_auto_perception_msgs::msg::ObjectClassification::BICYCLE); + EXPECT_EQ( + centerpoint::getSemanticType("MOTORBIKE"), + autoware_auto_perception_msgs::msg::ObjectClassification::MOTORCYCLE); + EXPECT_EQ( + centerpoint::getSemanticType("PEDESTRIAN"), + autoware_auto_perception_msgs::msg::ObjectClassification::PEDESTRIAN); + EXPECT_EQ( + centerpoint::getSemanticType("UNKNOWN"), + autoware_auto_perception_msgs::msg::ObjectClassification::UNKNOWN); +} + +TEST(TestSuite, convertPoseCovarianceMatrix) +{ + centerpoint::Box3D box3d; + box3d.x_variance = 0.1; + box3d.y_variance = 0.2; + box3d.z_variance = 0.3; + box3d.yaw_variance = 0.4; + + std::array pose_covariance = centerpoint::convertPoseCovarianceMatrix(box3d); + + EXPECT_FLOAT_EQ(pose_covariance[0], 0.1); + EXPECT_FLOAT_EQ(pose_covariance[7], 0.2); + EXPECT_FLOAT_EQ(pose_covariance[14], 0.3); + EXPECT_FLOAT_EQ(pose_covariance[35], 0.4); +} + +TEST(TestSuite, convertTwistCovarianceMatrix) +{ + centerpoint::Box3D box3d; + box3d.vel_x_variance = 0.1; + box3d.vel_y_variance = 0.2; + + std::array twist_covariance = centerpoint::convertTwistCovarianceMatrix(box3d); + + EXPECT_FLOAT_EQ(twist_covariance[0], 0.1); + EXPECT_FLOAT_EQ(twist_covariance[7], 0.2); +} + +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/perception/lidar_centerpoint/test/test_voxel_generator.cpp b/perception/lidar_centerpoint/test/test_voxel_generator.cpp new file mode 100644 index 0000000000000..5b0b3cd112e6c --- /dev/null +++ b/perception/lidar_centerpoint/test/test_voxel_generator.cpp @@ -0,0 +1,230 @@ +// 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 "test_voxel_generator.hpp" + +#include + +#include + +void VoxelGeneratorTest::SetUp() +{ + // Setup things that should occur before every test instance should go here + node_ = std::make_shared("voxel_generator_test_node"); + + world_frame_ = "map"; + lidar_frame_ = "lidar"; + points_per_pointcloud_ = 10; + capacity_ = 100; + delta_pointcloud_x_ = 1.0; + + class_size_ = 5; + point_feature_size_ = 4; + max_voxel_size_ = 100000000; + point_cloud_range_ = std::vector{-76.8, -76.8, -4.0, 76.8, 76.8, 6.0}; + voxel_size_ = std::vector{0.32, 0.32, 10.0}; + downsample_factor_ = 1; + encoder_in_feature_size_ = 9; + score_threshold_ = 0.35f; + circle_nms_dist_threshold_ = 0.5f; + yaw_norm_thresholds_ = std::vector{0.5, 0.5, 0.5}; + has_variance_ = false; + + cloud1_ = std::make_unique(); + cloud2_ = std::make_unique(); + + cloud1_->header.frame_id = lidar_frame_; + + // Set up the fields for x, y, and z coordinates + cloud1_->fields.resize(3); + sensor_msgs::PointCloud2Modifier modifier(*cloud1_); + modifier.setPointCloud2FieldsByString(1, "xyz"); + + // Resize the cloud to hold points_per_pointcloud_ points + modifier.resize(points_per_pointcloud_); + + // Create an iterator for the x, y, z fields + sensor_msgs::PointCloud2Iterator iter_x(*cloud1_, "x"); + sensor_msgs::PointCloud2Iterator iter_y(*cloud1_, "y"); + sensor_msgs::PointCloud2Iterator iter_z(*cloud1_, "z"); + + // Populate the point cloud + for (size_t i = 0; i < modifier.size(); ++i, ++iter_x, ++iter_y, ++iter_z) { + *iter_x = static_cast(i); + *iter_y = static_cast(i); + *iter_z = static_cast(i); + } + + *cloud2_ = *cloud1_; + + // Set the stamps for the point clouds. They usually come every 100ms + cloud1_->header.stamp.sec = 1; + cloud1_->header.stamp.nanosec = 100'000'000; + cloud2_->header.stamp.sec = 1; + cloud2_->header.stamp.nanosec = 200'000'000; + + tf2_buffer_ = std::make_unique(node_->get_clock()); + tf2_buffer_->setUsingDedicatedThread(true); + + // The vehicle moves 1m/s in the x direction + const double world_origin_x = 6'371'000.0; + const double world_origin_y = 1'371'000.0; + + transform1_.header.stamp = cloud1_->header.stamp; + transform1_.header.frame_id = world_frame_; + transform1_.child_frame_id = lidar_frame_; + transform1_.transform.translation.x = world_origin_x; + transform1_.transform.translation.y = world_origin_y; + transform1_.transform.translation.z = 1.8; + transform1_.transform.rotation.x = 0.0; + transform1_.transform.rotation.y = 0.0; + transform1_.transform.rotation.z = 0.0; + transform1_.transform.rotation.w = 1.0; + + transform2_ = transform1_; + transform2_.header.stamp = cloud2_->header.stamp; + transform2_.transform.translation.x = world_origin_x + delta_pointcloud_x_; +} + +void VoxelGeneratorTest::TearDown() +{ +} + +TEST_F(VoxelGeneratorTest, SingleFrame) +{ + const unsigned int num_past_frames = 0; // only current frame + + centerpoint::DensificationParam param(world_frame_, num_past_frames); + + centerpoint::CenterPointConfig config( + class_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_, has_variance_); + + centerpoint::VoxelGenerator voxel_generator(param, config); + std::vector points; + points.resize(capacity_ * config.point_feature_size_); + std::fill(points.begin(), points.end(), std::nan("")); + + bool status1 = voxel_generator.enqueuePointCloud(*cloud1_, *tf2_buffer_); + std::size_t generated_points_num = voxel_generator.generateSweepPoints(points); + + EXPECT_TRUE(status1); + EXPECT_EQ(points_per_pointcloud_, generated_points_num); + + // Check valid points + for (std::size_t i = 0; i < points_per_pointcloud_; ++i) { + // There are no tf conversions + EXPECT_EQ(static_cast(i), points[i * config.point_feature_size_ + 0]); + EXPECT_EQ(static_cast(i), points[i * config.point_feature_size_ + 1]); + EXPECT_EQ(static_cast(i), points[i * config.point_feature_size_ + 2]); + EXPECT_EQ(static_cast(0), points[i * config.point_feature_size_ + 3]); + } + + // Check invalid points + for (std::size_t i = points_per_pointcloud_ * config.point_feature_size_; + i < capacity_ * config.point_feature_size_; ++i) { + EXPECT_TRUE(std::isnan(points[i])); + } +} + +TEST_F(VoxelGeneratorTest, TwoFramesNoTf) +{ + const unsigned int num_past_frames = 1; + + centerpoint::DensificationParam param(world_frame_, num_past_frames); + + centerpoint::CenterPointConfig config( + class_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_, has_variance_); + + centerpoint::VoxelGenerator voxel_generator(param, config); + std::vector points; + points.resize(capacity_ * config.point_feature_size_); + std::fill(points.begin(), points.end(), std::nan("")); + + bool status1 = voxel_generator.enqueuePointCloud(*cloud1_, *tf2_buffer_); + bool status2 = voxel_generator.enqueuePointCloud(*cloud2_, *tf2_buffer_); + std::size_t generated_points_num = voxel_generator.generateSweepPoints(points); + + EXPECT_FALSE(status1); + EXPECT_FALSE(status2); + EXPECT_EQ(0, generated_points_num); +} + +TEST_F(VoxelGeneratorTest, TwoFrames) +{ + const unsigned int num_past_frames = 1; + + centerpoint::DensificationParam param(world_frame_, num_past_frames); + + centerpoint::CenterPointConfig config( + class_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_, has_variance_); + + centerpoint::VoxelGenerator voxel_generator(param, config); + std::vector points; + points.resize(capacity_ * config.point_feature_size_); + std::fill(points.begin(), points.end(), std::nan("")); + + tf2_buffer_->setTransform(transform1_, "authority1"); + tf2_buffer_->setTransform(transform2_, "authority1"); + + bool status1 = voxel_generator.enqueuePointCloud(*cloud1_, *tf2_buffer_); + bool status2 = voxel_generator.enqueuePointCloud(*cloud2_, *tf2_buffer_); + std::size_t generated_points_num = voxel_generator.generateSweepPoints(points); + + EXPECT_TRUE(status1); + EXPECT_TRUE(status2); + EXPECT_EQ(2 * points_per_pointcloud_, generated_points_num); + + // Check valid points for the latest pointcloud + for (std::size_t i = 0; i < points_per_pointcloud_; ++i) { + // There are no tf conversions + EXPECT_EQ(static_cast(i), points[i * config.point_feature_size_ + 0]); + EXPECT_EQ(static_cast(i), points[i * config.point_feature_size_ + 1]); + EXPECT_EQ(static_cast(i), points[i * config.point_feature_size_ + 2]); + EXPECT_EQ(static_cast(0), points[i * config.point_feature_size_ + 3]); + } + + // Check valid points for the oldest pointcloud + for (std::size_t i = 0; i < points_per_pointcloud_; ++i) { + // There are tf conversions, so results are not numerically the same + EXPECT_NEAR( + static_cast(i) - delta_pointcloud_x_, + points[(points_per_pointcloud_ + i) * config.point_feature_size_ + 0], 1e-6); + EXPECT_NEAR( + static_cast(i), points[(points_per_pointcloud_ + i) * config.point_feature_size_ + 1], + 1e-6); + EXPECT_NEAR( + static_cast(i), points[(points_per_pointcloud_ + i) * config.point_feature_size_ + 2], + 1e-6); + EXPECT_NEAR(0.1, points[(points_per_pointcloud_ + i) * config.point_feature_size_ + 3], 1e-6); + } + + // Check invalid points + for (std::size_t i = 2 * points_per_pointcloud_ * config.point_feature_size_; + i < capacity_ * config.point_feature_size_; ++i) { + EXPECT_TRUE(std::isnan(points[i])); + } +} + +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + rclcpp::init(argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/perception/lidar_centerpoint/test/test_voxel_generator.hpp b/perception/lidar_centerpoint/test/test_voxel_generator.hpp new file mode 100644 index 0000000000000..8fb7d8dffa44d --- /dev/null +++ b/perception/lidar_centerpoint/test/test_voxel_generator.hpp @@ -0,0 +1,66 @@ +// 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 TEST_VOXEL_GENERATOR_HPP_ +#define TEST_VOXEL_GENERATOR_HPP_ + +#include +#include + +#include + +#include + +#include +#include +#include + +class VoxelGeneratorTest : public testing::Test +{ +public: + void SetUp() override; + void TearDown() override; + + // These need to be public so that they can be accessed in the test cases + rclcpp::Node::SharedPtr node_; + + std::unique_ptr cloud1_, cloud2_; + geometry_msgs::msg::TransformStamped transform1_, transform2_; + + std::unique_ptr densification_param_ptr_; + std::unique_ptr config_ptr_; + + std::unique_ptr tf2_buffer_; + + std::string world_frame_; + std::string lidar_frame_; + std::size_t points_per_pointcloud_; + std::size_t capacity_; + double delta_pointcloud_x_; + + std::size_t class_size_; + float point_feature_size_; + std::size_t max_voxel_size_; + + std::vector point_cloud_range_; + std::vector voxel_size_; + std::size_t downsample_factor_; + std::size_t encoder_in_feature_size_; + float score_threshold_; + float circle_nms_dist_threshold_; + std::vector yaw_norm_thresholds_; + bool has_variance_; +}; + +#endif // TEST_VOXEL_GENERATOR_HPP_ diff --git a/perception/map_based_prediction/CMakeLists.txt b/perception/map_based_prediction/CMakeLists.txt index 9378e09f099cc..786446457143f 100644 --- a/perception/map_based_prediction/CMakeLists.txt +++ b/perception/map_based_prediction/CMakeLists.txt @@ -26,6 +26,22 @@ rclcpp_components_register_node(map_based_prediction_node EXECUTABLE map_based_prediction ) +## Tests +if(BUILD_TESTING) + find_package(ament_cmake_ros REQUIRED) + list(APPEND AMENT_LINT_AUTO_EXCLUDE ament_cmake_uncrustify) + + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + + file(GLOB_RECURSE test_files test/**/*.cpp) + ament_add_ros_isolated_gtest(test_map_based_prediction ${test_files}) + + target_link_libraries(test_map_based_prediction + map_based_prediction_node + ) +endif() + ament_auto_package( INSTALL_TO_SHARE config 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..a5b7b0ad6be01 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] @@ -27,6 +30,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..93cdb24f91321 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; @@ -99,6 +106,14 @@ struct PredictedRefPath Maneuver maneuver; }; +struct PredictionTimeHorizon +{ + // NOTE(Mamoru Sobue): motorcycle belongs to "vehicle" and bicycle to "pedestrian" + double vehicle; + double pedestrian; + double unknown; +}; + using LaneletsData = std::vector; using ManeuverProbability = std::unordered_map; using autoware_auto_mapping_msgs::msg::HADMapBin; @@ -135,8 +150,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_; @@ -161,7 +178,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_; @@ -200,6 +217,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 +242,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,13 +251,17 @@ 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); + 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..3c1a5432d3b08 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,24 @@ 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) const; - 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) const; 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) const; 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,35 +114,36 @@ 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) const; 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) const; Eigen::Vector3d calcLatCoefficients( - const FrenetPoint & current_point, const FrenetPoint & target_point, const double T); + const FrenetPoint & current_point, const FrenetPoint & target_point, const double T) const; Eigen::Vector2d calcLonCoefficients( - const FrenetPoint & current_point, const FrenetPoint & target_point, const double T); + const FrenetPoint & current_point, const FrenetPoint & target_point, const double T) const; PosePath interpolateReferencePath( - const PosePath & base_path, const FrenetPath & frenet_predicted_path); + const PosePath & base_path, const FrenetPath & frenet_predicted_path) const; PredictedPath convertToPredictedPath( const TrackedObject & object, const FrenetPath & frenet_predicted_path, - const PosePath & ref_path); + const PosePath & ref_path) const; 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) const; }; } // namespace map_based_prediction diff --git a/perception/map_based_prediction/package.xml b/perception/map_based_prediction/package.xml index 8efea9efa1844..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 @@ -17,9 +16,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/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 56dc1c2293583..9b527fafb30e9 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 * @@ -715,10 +761,15 @@ 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"); + 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"); @@ -774,7 +825,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_ = @@ -789,8 +843,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_); @@ -916,7 +969,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; @@ -926,6 +991,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; @@ -946,6 +1025,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); @@ -963,12 +1048,12 @@ 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()) { - 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; @@ -983,8 +1068,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; @@ -996,13 +1081,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; @@ -1037,7 +1123,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_) { @@ -1100,8 +1187,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); @@ -1111,6 +1198,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); @@ -1123,6 +1223,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 = @@ -1139,7 +1312,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], @@ -1168,7 +1341,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); @@ -1219,7 +1393,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); @@ -1229,7 +1403,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); @@ -1253,27 +1427,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()) { @@ -1343,49 +1517,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(), @@ -1500,9 +1634,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) == @@ -1569,7 +1703,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) { @@ -1593,13 +1727,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( @@ -1611,7 +1745,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, @@ -1623,7 +1757,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 { @@ -1787,10 +1921,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()) { @@ -1826,11 +1960,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; @@ -1897,11 +2031,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 @@ -2058,12 +2192,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) == diff --git a/perception/map_based_prediction/src/path_generator.cpp b/perception/map_based_prediction/src/path_generator.cpp index 413a0e233186b..838d7b1c8e316 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) const { - return generateStraightPath(object); + return generateStraightPath(object, duration); } PredictedPath PathGenerator::generatePathToTargetPoint( @@ -50,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; @@ -71,7 +73,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,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; - for (double dt = 0.0; dt < time_horizon_ + ep; dt += sampling_time_interval_) { + 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()) { @@ -114,56 +124,49 @@ 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_); 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) const { - 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) const { 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) const { // 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) const { 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 = @@ -252,7 +255,7 @@ FrenetPath PathGenerator::generateFrenetPath( } Eigen::Vector3d PathGenerator::calcLatCoefficients( - const FrenetPoint & current_point, const FrenetPoint & target_point, const double T) + const FrenetPoint & current_point, const FrenetPoint & target_point, const double T) const { // Lateral Path Calculation // Quintic polynomial for d @@ -278,7 +281,7 @@ Eigen::Vector3d PathGenerator::calcLatCoefficients( } Eigen::Vector2d PathGenerator::calcLonCoefficients( - const FrenetPoint & current_point, const FrenetPoint & target_point, const double T) + const FrenetPoint & current_point, const FrenetPoint & target_point, const double T) const { // Longitudinal Path Calculation // Quadric polynomial @@ -296,7 +299,7 @@ Eigen::Vector2d PathGenerator::calcLonCoefficients( } PosePath PathGenerator::interpolateReferencePath( - const PosePath & base_path, const FrenetPath & frenet_predicted_path) + const PosePath & base_path, const FrenetPath & frenet_predicted_path) const { PosePath interpolated_path; const size_t interpolate_num = frenet_predicted_path.size(); @@ -356,7 +359,8 @@ PosePath PathGenerator::interpolateReferencePath( } PredictedPath PathGenerator::convertToPredictedPath( - const TrackedObject & object, const FrenetPath & frenet_predicted_path, const PosePath & ref_path) + const TrackedObject & object, const FrenetPath & frenet_predicted_path, + const PosePath & ref_path) const { PredictedPath predicted_path; predicted_path.time_step = rclcpp::Duration::from_seconds(sampling_time_interval_); @@ -385,7 +389,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) const { FrenetPoint frenet_point; const auto obj_point = object.kinematics.pose_with_covariance.pose.position; @@ -411,7 +416,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 { diff --git a/perception/map_based_prediction/test/map_based_prediction/test_path_generator.cpp b/perception/map_based_prediction/test/map_based_prediction/test_path_generator.cpp new file mode 100644 index 0000000000000..6134f0c6a25d7 --- /dev/null +++ b/perception/map_based_prediction/test/map_based_prediction/test_path_generator.cpp @@ -0,0 +1,207 @@ +// 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 "map_based_prediction/path_generator.hpp" + +#include +#include + +using autoware_auto_perception_msgs::msg::ObjectClassification; +using autoware_auto_perception_msgs::msg::PredictedObject; +using autoware_auto_perception_msgs::msg::PredictedObjectKinematics; +using autoware_auto_perception_msgs::msg::PredictedObjects; +using autoware_auto_perception_msgs::msg::PredictedPath; +using autoware_auto_perception_msgs::msg::TrackedObject; +using autoware_auto_perception_msgs::msg::TrackedObjectKinematics; +using autoware_auto_perception_msgs::msg::TrackedObjects; + +TrackedObject generate_static_object(const int label) +{ + ObjectClassification classification; + classification.probability = 1.0; + classification.label = label; + + TrackedObjectKinematics kinematics; + kinematics.pose_with_covariance = geometry_msgs::msg::PoseWithCovariance(); // At origin + kinematics.twist_with_covariance = geometry_msgs::msg::TwistWithCovariance(); // Not moving + kinematics.acceleration_with_covariance = + geometry_msgs::msg::AccelWithCovariance(); // Not accelerating + kinematics.orientation_availability = TrackedObjectKinematics::UNAVAILABLE; + + TrackedObject tracked_object; + tracked_object.object_id = unique_identifier_msgs::msg::UUID(); + tracked_object.existence_probability = 1.0; + tracked_object.classification.push_back(classification); + tracked_object.kinematics = kinematics; + + return tracked_object; +} + +TEST(PathGenerator, test_generatePathForNonVehicleObject) +{ + // Generate Path generator + const double prediction_time_horizon = 10.0; + const double prediction_sampling_time_interval = 0.5; + const double min_crosswalk_user_velocity = 0.1; + const map_based_prediction::PathGenerator path_generator = map_based_prediction::PathGenerator( + prediction_sampling_time_interval, min_crosswalk_user_velocity); + + // Generate pedestrian object + TrackedObject tracked_object = generate_static_object(ObjectClassification::PEDESTRIAN); + + // Generate predicted path + const PredictedPath predicted_path = + path_generator.generatePathForNonVehicleObject(tracked_object, prediction_time_horizon); + + // Check + EXPECT_FALSE(predicted_path.path.empty()); + EXPECT_EQ(predicted_path.path[0].position.x, 0.0); + EXPECT_EQ(predicted_path.path[0].position.y, 0.0); + EXPECT_EQ(predicted_path.path[0].position.z, 0.0); +} + +TEST(PathGenerator, test_generatePathForLowSpeedVehicle) +{ + // Generate Path generator + const double prediction_time_horizon = 10.0; + const double prediction_sampling_time_interval = 0.5; + const double min_crosswalk_user_velocity = 0.1; + const map_based_prediction::PathGenerator path_generator = map_based_prediction::PathGenerator( + prediction_sampling_time_interval, min_crosswalk_user_velocity); + + // Generate dummy object + TrackedObject tracked_object = generate_static_object(ObjectClassification::CAR); + + // Generate predicted path + const PredictedPath predicted_path = + path_generator.generatePathForLowSpeedVehicle(tracked_object, prediction_time_horizon); + + // Check + EXPECT_FALSE(predicted_path.path.empty()); + EXPECT_EQ(predicted_path.path[0].position.x, 0.0); + EXPECT_EQ(predicted_path.path[0].position.y, 0.0); + EXPECT_EQ(predicted_path.path[0].position.z, 0.0); +} + +TEST(PathGenerator, test_generatePathForOffLaneVehicle) +{ + // Generate Path generator + const double prediction_time_horizon = 10.0; + const double prediction_sampling_time_interval = 0.5; + const double min_crosswalk_user_velocity = 0.1; + const map_based_prediction::PathGenerator path_generator = map_based_prediction::PathGenerator( + prediction_sampling_time_interval, min_crosswalk_user_velocity); + + // Generate dummy object + TrackedObject tracked_object = generate_static_object(ObjectClassification::CAR); + + const PredictedPath predicted_path = + path_generator.generatePathForOffLaneVehicle(tracked_object, prediction_time_horizon); + + // Check + EXPECT_FALSE(predicted_path.path.empty()); + EXPECT_EQ(predicted_path.path[0].position.x, 0.0); + EXPECT_EQ(predicted_path.path[0].position.y, 0.0); + EXPECT_EQ(predicted_path.path[0].position.z, 0.0); +} + +TEST(PathGenerator, test_generatePathForOnLaneVehicle) +{ + // Generate Path generator + const double prediction_time_horizon = 10.0; + const double lateral_control_time_horizon = 5.0; + const double prediction_sampling_time_interval = 0.5; + const double min_crosswalk_user_velocity = 0.1; + const map_based_prediction::PathGenerator path_generator = map_based_prediction::PathGenerator( + prediction_sampling_time_interval, min_crosswalk_user_velocity); + + // Generate dummy object + TrackedObject tracked_object = generate_static_object(ObjectClassification::CAR); + + // Generate reference path + map_based_prediction::PosePath ref_paths; + geometry_msgs::msg::Pose pose; + pose.position.x = 0.0; + pose.position.y = 0.0; + pose.position.z = 0.0; + ref_paths.push_back(pose); + + // Generate predicted path + const PredictedPath predicted_path = path_generator.generatePathForOnLaneVehicle( + tracked_object, ref_paths, prediction_time_horizon, lateral_control_time_horizon); + + // Check + EXPECT_FALSE(predicted_path.path.empty()); + EXPECT_EQ(predicted_path.path[0].position.x, 0.0); + EXPECT_EQ(predicted_path.path[0].position.y, 0.0); + EXPECT_EQ(predicted_path.path[0].position.z, 0.0); +} + +TEST(PathGenerator, test_generatePathForCrosswalkUser) +{ + // Generate Path generator + const double prediction_time_horizon = 10.0; + const double prediction_sampling_time_interval = 0.5; + const double min_crosswalk_user_velocity = 0.1; + const map_based_prediction::PathGenerator path_generator = map_based_prediction::PathGenerator( + prediction_sampling_time_interval, min_crosswalk_user_velocity); + + // Generate dummy object + TrackedObject tracked_object = generate_static_object(ObjectClassification::PEDESTRIAN); + + // Generate dummy crosswalk + map_based_prediction::CrosswalkEdgePoints reachable_crosswalk; + reachable_crosswalk.front_center_point << 0.0, 0.0; + reachable_crosswalk.front_right_point << 1.0, 0.0; + reachable_crosswalk.front_left_point << -1.0, 0.0; + reachable_crosswalk.back_center_point << 0.0, 1.0; + reachable_crosswalk.back_right_point << 1.0, 1.0; + reachable_crosswalk.back_left_point << -1.0, 1.0; + + // Generate predicted path + const PredictedPath predicted_path = path_generator.generatePathForCrosswalkUser( + tracked_object, reachable_crosswalk, prediction_time_horizon); + + // Check + EXPECT_FALSE(predicted_path.path.empty()); + EXPECT_EQ(predicted_path.path[0].position.x, 0.0); + EXPECT_EQ(predicted_path.path[0].position.y, 0.0); + EXPECT_EQ(predicted_path.path[0].position.z, 0.0); +} + +TEST(PathGenerator, test_generatePathToTargetPoint) +{ + // Generate Path generator + const double prediction_sampling_time_interval = 0.5; + const double min_crosswalk_user_velocity = 0.1; + const map_based_prediction::PathGenerator path_generator = map_based_prediction::PathGenerator( + prediction_sampling_time_interval, min_crosswalk_user_velocity); + + // Generate dummy object + TrackedObject tracked_object = generate_static_object(ObjectClassification::CAR); + + // Generate target point + Eigen::Vector2d target_point; + target_point << 0.0, 0.0; + + // Generate predicted path + const PredictedPath predicted_path = + path_generator.generatePathToTargetPoint(tracked_object, target_point); + + // Check + EXPECT_FALSE(predicted_path.path.empty()); + EXPECT_EQ(predicted_path.path[0].position.x, 0.0); + EXPECT_EQ(predicted_path.path[0].position.y, 0.0); + EXPECT_EQ(predicted_path.path[0].position.z, 0.0); +} diff --git a/map/map_projection_loader/src/map_projection_loader_node.cpp b/perception/map_based_prediction/test/test_map_based_prediction.cpp similarity index 78% rename from map/map_projection_loader/src/map_projection_loader_node.cpp rename to perception/map_based_prediction/test/test_map_based_prediction.cpp index 1d9336be0d9dd..4c8ad7dd25916 100644 --- a/map/map_projection_loader/src/map_projection_loader_node.cpp +++ b/perception/map_based_prediction/test/test_map_based_prediction.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 TIER IV, Inc. +// 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. @@ -12,12 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "map_projection_loader/map_projection_loader.hpp" +#include + +#include int main(int argc, char * argv[]) { + testing::InitGoogleTest(&argc, argv); rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()); + bool result = RUN_ALL_TESTS(); rclcpp::shutdown(); - return 0; + return result; } diff --git a/perception/multi_object_tracker/CMakeLists.txt b/perception/multi_object_tracker/CMakeLists.txt index 41d150ef0ba1b..4f9268583dd34 100644 --- a/perception/multi_object_tracker/CMakeLists.txt +++ b/perception/multi_object_tracker/CMakeLists.txt @@ -22,8 +22,10 @@ include_directories( # Generate exe file set(MULTI_OBJECT_TRACKER_SRC src/multi_object_tracker_core.cpp - src/debugger.cpp + src/debugger/debugger.cpp + src/debugger/debug_object.cpp src/processor/processor.cpp + src/processor/input_manager.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 @@ -42,20 +44,18 @@ set(MULTI_OBJECT_TRACKER_SRC src/tracker/model/pass_through_tracker.cpp ) -ament_auto_add_library(multi_object_tracker_node SHARED +ament_auto_add_library(${PROJECT_NAME} SHARED ${MULTI_OBJECT_TRACKER_SRC} ) -target_link_libraries(multi_object_tracker_node +target_link_libraries(${PROJECT_NAME} 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 +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "multi_object_tracker::MultiObjectTracker" + EXECUTABLE ${PROJECT_NAME}_node ) ament_auto_package(INSTALL_TO_SHARE diff --git a/perception/multi_object_tracker/README.md b/perception/multi_object_tracker/README.md index 311fe7b6da716..ad9e43355aebf 100644 --- a/perception/multi_object_tracker/README.md +++ b/perception/multi_object_tracker/README.md @@ -46,31 +46,38 @@ Example: ### Input -| Name | Type | Description | -| --------- | ----------------------------------------------------- | ----------- | -| `~/input` | `autoware_auto_perception_msgs::msg::DetectedObjects` | obstacles | +Multiple inputs are pre-defined in the input channel parameters (described below) and the inputs can be configured + +| Name | Type | Description | +| ------------------------- | -------------------------- | ---------------------- | +| `selected_input_channels` | `std::vector` | array of channel names | + +- default value: `selected_input_channels:="['detected_objects']"`, merged DetectedObject message +- multi-input example: `selected_input_channels:="['lidar_centerpoint','camera_lidar_fusion','detection_by_tracker','radar_far']"` ### Output -| Name | Type | Description | -| ---------- | ---------------------------------------------------- | ------------------ | -| `~/output` | `autoware_auto_perception_msgs::msg::TrackedObjects` | modified obstacles | +| Name | Type | Description | +| ---------- | ---------------------------------------------------- | --------------- | +| `~/output` | `autoware_auto_perception_msgs::msg::TrackedObjects` | tracked objects | ## Parameters - +| Name | Type | Description | +| --------------------------------- | ----------------------------------------------------- | ------------------------------------- | +| `` | | the name of channel | +| `.topic` | `autoware_auto_perception_msgs::msg::DetectedObjects` | detected objects | +| `.can_spawn_new_tracker` | `bool` | a switch allow to spawn a new tracker | +| `.optional.name` | `std::string` | channel name for analysis | +| `.optional.short_name` | `std::string` | short name for visualization | ### Core Parameters -Node parameters are defined in [multi_object_tracker.param.yaml](config/multi_object_tracker.param.yaml) and association parameters are defined in [data_association.param.yaml](config/data_association.param.yaml). +Node parameters are defined in [multi_object_tracker_node.param.yaml](config/multi_object_tracker_node.param.yaml) and association parameters are defined in [data_association_matrix.param.yaml](config/data_association_matrix.param.yaml). #### Node parameters @@ -80,6 +87,9 @@ Node parameters are defined in [multi_object_tracker.param.yaml](config/multi_ob | `world_frame_id` | double | object kinematics definition frame | | `enable_delay_compensation` | bool | if True, tracker use timers to schedule publishers and use prediction step to extrapolate object state at desired timestamp | | `publish_rate` | double | Timer frequency to output with delay compensation | +| `publish_processing_time` | bool | enable to publish debug message of process time information | +| `publish_tentative_objects` | bool | enable to publish tentative tracked objects, which have lower confidence | +| `publish_debug_markers` | bool | enable to publish debug markers, which indicates association of multi-inputs, existence probability of each detection | #### Association parameters @@ -93,13 +103,6 @@ Node parameters are defined in [multi_object_tracker.param.yaml](config/multi_ob ## Assumptions / Known limits - - See the [model explanations](models.md). ## (Optional) Error detection and handling diff --git a/perception/multi_object_tracker/config/input_channels.param.yaml b/perception/multi_object_tracker/config/input_channels.param.yaml new file mode 100644 index 0000000000000..b57f37675d4f1 --- /dev/null +++ b/perception/multi_object_tracker/config/input_channels.param.yaml @@ -0,0 +1,82 @@ +/**: + ros__parameters: + input_channels: + detected_objects: + topic: "/perception/object_recognition/detection/objects" + can_spawn_new_tracker: true + optional: + name: "detected_objects" + short_name: "all" + # LIDAR - rule-based + lidar_clustering: + topic: "/perception/object_recognition/detection/clustering/objects" + can_spawn_new_tracker: true + optional: + name: "clustering" + short_name: "Lcl" + # LIDAR - DNN + lidar_centerpoint: + topic: "/perception/object_recognition/detection/centerpoint/objects" + can_spawn_new_tracker: true + optional: + name: "centerpoint" + short_name: "Lcp" + lidar_centerpoint_validated: + topic: "/perception/object_recognition/detection/centerpoint/validation/objects" + can_spawn_new_tracker: true + optional: + name: "centerpoint" + short_name: "Lcp" + lidar_apollo: + topic: "/perception/object_recognition/detection/apollo/objects" + can_spawn_new_tracker: true + optional: + name: "apollo" + short_name: "Lap" + lidar_apollo_validated: + topic: "/perception/object_recognition/detection/apollo/validation/objects" + can_spawn_new_tracker: true + optional: + name: "apollo" + short_name: "Lap" + # LIDAR-CAMERA - DNN + # cspell:ignore lidar_pointpainitng pointpainting + lidar_pointpainitng: + topic: "/perception/object_recognition/detection/pointpainting/objects" + can_spawn_new_tracker: true + optional: + name: "pointpainting" + short_name: "Lpp" + lidar_pointpainting_validated: + topic: "/perception/object_recognition/detection/pointpainting/validation/objects" + can_spawn_new_tracker: true + optional: + name: "pointpainting" + short_name: "Lpp" + # CAMERA-LIDAR + camera_lidar_fusion: + topic: "/perception/object_recognition/detection/clustering/camera_lidar_fusion/objects" + can_spawn_new_tracker: true + optional: + name: "camera_lidar_fusion" + short_name: "CLf" + # CAMERA-LIDAR+TRACKER + detection_by_tracker: + topic: "/perception/object_recognition/detection/detection_by_tracker/objects" + can_spawn_new_tracker: false + optional: + name: "detection_by_tracker" + short_name: "dbT" + # RADAR + radar: + topic: "/sensing/radar/detected_objects" + can_spawn_new_tracker: true + optional: + name: "radar" + short_name: "R" + radar_far: + topic: "/perception/object_recognition/detection/radar/far_objects" + can_spawn_new_tracker: true + optional: + name: "radar_far" + short_name: "Rf" diff --git a/perception/multi_object_tracker/config/multi_object_tracker_node.param.yaml b/perception/multi_object_tracker/config/multi_object_tracker_node.param.yaml index ca320c7f58442..09621a40c499f 100644 --- a/perception/multi_object_tracker/config/multi_object_tracker_node.param.yaml +++ b/perception/multi_object_tracker/config/multi_object_tracker_node.param.yaml @@ -17,5 +17,6 @@ # debug parameters publish_processing_time: false publish_tentative_objects: false + publish_debug_markers: false diagnostics_warn_delay: 0.5 # [sec] diagnostics_error_delay: 1.0 # [sec] diff --git a/perception/multi_object_tracker/include/multi_object_tracker/debugger/debug_object.hpp b/perception/multi_object_tracker/include/multi_object_tracker/debugger/debug_object.hpp new file mode 100644 index 0000000000000..6caa69181dd9d --- /dev/null +++ b/perception/multi_object_tracker/include/multi_object_tracker/debugger/debug_object.hpp @@ -0,0 +1,102 @@ +// 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__DEBUGGER__DEBUG_OBJECT_HPP_ +#define MULTI_OBJECT_TRACKER__DEBUGGER__DEBUG_OBJECT_HPP_ + +#include "multi_object_tracker/tracker/model/tracker_base.hpp" + +#include +#include + +#include "unique_identifier_msgs/msg/uuid.hpp" +#include +#include +#include +#include + +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +struct ObjectData +{ + rclcpp::Time time; + + // object uuid + boost::uuids::uuid uuid; + int uuid_int; + std::string uuid_str; + + // association link, pair of coordinates + // tracker to detection + geometry_msgs::msg::Point tracker_point; + geometry_msgs::msg::Point detection_point; + bool is_associated{false}; + + // existence probabilities + std::vector existence_vector; + + // detection channel id + uint channel_id; +}; + +class TrackerObjectDebugger +{ +public: + explicit TrackerObjectDebugger(std::string frame_id); + +private: + bool is_initialized_{false}; + std::string frame_id_; + visualization_msgs::msg::MarkerArray markers_; + std::unordered_set current_ids_; + std::unordered_set previous_ids_; + rclcpp::Time message_time_; + + std::vector object_data_list_; + std::list unused_marker_ids_; + int32_t marker_id_ = 0; + std::vector> object_data_groups_; + + std::vector channel_names_; + +public: + void setChannelNames(const std::vector & channel_names) + { + channel_names_ = channel_names; + } + void collect( + const rclcpp::Time & message_time, const std::list> & list_tracker, + const uint & channel_index, + const autoware_auto_perception_msgs::msg::DetectedObjects & detected_objects, + const std::unordered_map & direct_assignment, + const std::unordered_map & reverse_assignment); + + void reset(); + void draw( + const std::vector> object_data_groups, + visualization_msgs::msg::MarkerArray & marker_array) const; + void process(); + void getMessage(visualization_msgs::msg::MarkerArray & marker_array) const; +}; + +#endif // MULTI_OBJECT_TRACKER__DEBUGGER__DEBUG_OBJECT_HPP_ diff --git a/perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp b/perception/multi_object_tracker/include/multi_object_tracker/debugger/debugger.hpp similarity index 66% rename from perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp rename to perception/multi_object_tracker/include/multi_object_tracker/debugger/debugger.hpp index 90291ae6fec18..1c632f5bebba0 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/debugger.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/debugger/debugger.hpp @@ -1,4 +1,4 @@ -// Copyright 2024 Tier IV, Inc. +// 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. @@ -11,11 +11,11 @@ // 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__DEBUGGER_HPP_ -#define MULTI_OBJECT_TRACKER__DEBUGGER_HPP_ +#ifndef MULTI_OBJECT_TRACKER__DEBUGGER__DEBUGGER_HPP_ +#define MULTI_OBJECT_TRACKER__DEBUGGER__DEBUGGER_HPP_ + +#include "multi_object_tracker/debugger/debug_object.hpp" #include #include @@ -27,7 +27,11 @@ #include #include +#include #include +#include +#include +#include /** * @brief Debugger class for multi object tracker @@ -36,40 +40,68 @@ class TrackerDebugger { public: - explicit TrackerDebugger(rclcpp::Node & node); - void publishTentativeObjects( - 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); + explicit TrackerDebugger(rclcpp::Node & node, const std::string & frame_id); - void setupDiagnostics(); - void checkDelay(diagnostic_updater::DiagnosticStatusWrapper & stat); +private: struct DEBUG_SETTINGS { bool publish_processing_time; bool publish_tentative_objects; + bool publish_debug_markers; double diagnostics_warn_delay; double diagnostics_error_delay; } 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(); - bool is_initialized_ = false; + // ROS node, publishers rclcpp::Node & node_; rclcpp::Publisher::SharedPtr debug_tentative_objects_pub_; std::unique_ptr processing_time_publisher_; + rclcpp::Publisher::SharedPtr debug_objects_markers_pub_; + + diagnostic_updater::Updater diagnostic_updater_; + // Object debugger + TrackerObjectDebugger object_debugger_; + + // Time measurement + bool is_initialized_ = false; + double pipeline_latency_ms_ = 0.0; 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_; + + // Configuration + void setupDiagnostics(); + void loadParameters(); + +public: + // Object publishing + bool shouldPublishTentativeObjects() const { return debug_settings_.publish_tentative_objects; } + void publishTentativeObjects( + const autoware_auto_perception_msgs::msg::TrackedObjects & tentative_objects) const; + + // Time measurement + 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 checkDelay(diagnostic_updater::DiagnosticStatusWrapper & stat); + + // Debug object + void setObjectChannels(const std::vector & channels) + { + object_debugger_.setChannelNames(channels); + } + void collectObjectInfo( + const rclcpp::Time & message_time, const std::list> & list_tracker, + const uint & channel_index, + const autoware_auto_perception_msgs::msg::DetectedObjects & detected_objects, + const std::unordered_map & direct_assignment, + const std::unordered_map & reverse_assignment); + void publishObjectsMarkers(); }; -#endif // MULTI_OBJECT_TRACKER__DEBUGGER_HPP_ +#endif // MULTI_OBJECT_TRACKER__DEBUGGER__DEBUGGER_HPP_ 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 f788dd3895216..3daeaa2a46322 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 @@ -20,7 +20,8 @@ #define MULTI_OBJECT_TRACKER__MULTI_OBJECT_TRACKER_CORE_HPP_ #include "multi_object_tracker/data_association/data_association.hpp" -#include "multi_object_tracker/debugger.hpp" +#include "multi_object_tracker/debugger/debugger.hpp" +#include "multi_object_tracker/processor/input_manager.hpp" #include "multi_object_tracker/processor/processor.hpp" #include "multi_object_tracker/tracker/model/tracker_base.hpp" @@ -48,8 +49,16 @@ #include #include #include +#include #include +namespace multi_object_tracker +{ + +using DetectedObject = autoware_auto_perception_msgs::msg::DetectedObject; +using DetectedObjects = autoware_auto_perception_msgs::msg::DetectedObjects; +using TrackedObjects = autoware_auto_perception_msgs::msg::TrackedObjects; + class MultiObjectTracker : public rclcpp::Node { public: @@ -57,10 +66,8 @@ class MultiObjectTracker : public rclcpp::Node private: // ROS interface - rclcpp::Publisher::SharedPtr - tracked_objects_pub_; - rclcpp::Subscription::SharedPtr - detected_object_sub_; + rclcpp::Publisher::SharedPtr tracked_objects_pub_; + rclcpp::Subscription::SharedPtr detected_object_sub_; tf2_ros::Buffer tf_buffer_; tf2_ros::TransformListener tf_listener_; @@ -78,15 +85,24 @@ class MultiObjectTracker : public rclcpp::Node std::unique_ptr data_association_; std::unique_ptr processor_; + // input manager + std::unique_ptr input_manager_; + + std::vector input_channels_{}; + size_t input_channel_size_{}; + // callback functions - void onMeasurement( - const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr input_objects_msg); void onTimer(); + void onTrigger(); + void onMessage(const ObjectsList & objects_list); // publish processes + void runProcess(const DetectedObjects & input_objects_msg, const uint & channel_index); void checkAndPublish(const rclcpp::Time & time); void publish(const rclcpp::Time & time) const; inline bool shouldTrackerPublish(const std::shared_ptr tracker) const; }; +} // namespace multi_object_tracker + #endif // MULTI_OBJECT_TRACKER__MULTI_OBJECT_TRACKER_CORE_HPP_ diff --git a/perception/multi_object_tracker/include/multi_object_tracker/processor/input_manager.hpp b/perception/multi_object_tracker/include/multi_object_tracker/processor/input_manager.hpp new file mode 100644 index 0000000000000..f46c088c6d508 --- /dev/null +++ b/perception/multi_object_tracker/include/multi_object_tracker/processor/input_manager.hpp @@ -0,0 +1,160 @@ +// 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__INPUT_MANAGER_HPP_ +#define MULTI_OBJECT_TRACKER__PROCESSOR__INPUT_MANAGER_HPP_ + +#include "rclcpp/rclcpp.hpp" + +#include "autoware_auto_perception_msgs/msg/detected_objects.hpp" + +#include +#include +#include +#include +#include +#include + +namespace multi_object_tracker +{ +using DetectedObjects = autoware_auto_perception_msgs::msg::DetectedObjects; +using ObjectsList = std::vector>; + +struct InputChannel +{ + std::string input_topic; // topic name of the detection, e.g. "/detection/lidar" + std::string long_name = "Detected Object"; // full name of the detection + std::string short_name = "DET"; // abbreviation of the name + bool is_spawn_enabled = true; // enable spawn of the object +}; + +class InputStream +{ +public: + explicit InputStream(rclcpp::Node & node, uint & index); + + void init(const InputChannel & input_channel); + + void setQueueSize(size_t que_size) { que_size_ = que_size; } + void setTriggerFunction(std::function func_trigger) + { + func_trigger_ = func_trigger; + } + + void onMessage(const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr msg); + void updateTimingStatus(const rclcpp::Time & now, const rclcpp::Time & objects_time); + + bool isTimeInitialized() const { return initial_count_ > 0; } + uint getIndex() const { return index_; } + void getObjectsOlderThan( + const rclcpp::Time & object_latest_time, const rclcpp::Time & object_oldest_time, + ObjectsList & objects_list); + void getNames(std::string & long_name, std::string & short_name) + { + long_name = long_name_; + short_name = short_name_; + } + bool isSpawnEnabled() const { return is_spawn_enabled_; } + + std::string getLongName() const { return long_name_; } + size_t getObjectsCount() const { return objects_que_.size(); } + void getTimeStatistics( + double & latency_mean, double & latency_var, double & interval_mean, + double & interval_var) const + { + latency_mean = latency_mean_; + latency_var = latency_var_; + interval_mean = interval_mean_; + interval_var = interval_var_; + } + void getLatencyStatistics(double & latency_mean, double & latency_var) const + { + latency_mean = latency_mean_; + latency_var = latency_var_; + } + bool getTimestamps( + rclcpp::Time & latest_measurement_time, rclcpp::Time & latest_message_time) const; + rclcpp::Time getLatestMeasurementTime() const { return latest_measurement_time_; } + +private: + rclcpp::Node & node_; + uint index_; + + std::string input_topic_; + std::string long_name_; + std::string short_name_; + bool is_spawn_enabled_; + + size_t que_size_{30}; + std::deque objects_que_; + + std::function func_trigger_; + + // bool is_time_initialized_{false}; + int initial_count_{0}; + double expected_interval_; + double latency_mean_; + double latency_var_; + double interval_mean_; + double interval_var_; + + rclcpp::Time latest_measurement_time_; + rclcpp::Time latest_message_time_; +}; + +class InputManager +{ +public: + explicit InputManager(rclcpp::Node & node); + void init(const std::vector & input_channels); + + void setTriggerFunction(std::function func_trigger) { func_trigger_ = func_trigger; } + void onTrigger(const uint & index) const; + + bool getObjects(const rclcpp::Time & now, ObjectsList & objects_list); + + bool isChannelSpawnEnabled(const uint & index) const + { + return input_streams_[index]->isSpawnEnabled(); + } + +private: + rclcpp::Node & node_; + std::vector::SharedPtr> sub_objects_array_{}; + + bool is_initialized_{false}; + rclcpp::Time latest_exported_object_time_; + + size_t input_size_; + std::vector> input_streams_; + + std::function func_trigger_; + uint target_stream_idx_{0}; + double target_stream_latency_{0.2}; // [s] + double target_stream_latency_std_{0.04}; // [s] + double target_stream_interval_{0.1}; // [s] + double target_stream_interval_std_{0.02}; // [s] + double target_latency_{0.2}; // [s] + double target_latency_band_{1.0}; // [s] + +private: + void getObjectTimeInterval( + const rclcpp::Time & now, rclcpp::Time & object_latest_time, + rclcpp::Time & object_oldest_time) const; + void optimizeTimings(); +}; + +} // namespace multi_object_tracker + +#endif // MULTI_OBJECT_TRACKER__PROCESSOR__INPUT_MANAGER_HPP_ 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 index 6d6e364d83a41..310871dfcb07a 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/processor/processor.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/processor/processor.hpp @@ -1,4 +1,4 @@ -// Copyright 2024 Tier IV, Inc. +// 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. @@ -11,8 +11,6 @@ // 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_ @@ -34,7 +32,8 @@ class TrackerProcessor { public: - explicit TrackerProcessor(const std::map & tracker_map); + explicit TrackerProcessor( + const std::map & tracker_map, const size_t & channel_size); const std::list> & getListTracker() const { return list_tracker_; } // tracker processes @@ -42,11 +41,11 @@ class TrackerProcessor void update( const autoware_auto_perception_msgs::msg::DetectedObjects & transformed_objects, const geometry_msgs::msg::Transform & self_transform, - const std::unordered_map & direct_assignment); + const std::unordered_map & direct_assignment, const uint & channel_index); void spawn( const autoware_auto_perception_msgs::msg::DetectedObjects & detected_objects, const geometry_msgs::msg::Transform & self_transform, - const std::unordered_map & reverse_assignment); + const std::unordered_map & reverse_assignment, const uint & channel_index); void prune(const rclcpp::Time & time); // output @@ -58,9 +57,12 @@ class TrackerProcessor const rclcpp::Time & time, autoware_auto_perception_msgs::msg::TrackedObjects & tentative_objects) const; + void getExistenceProbabilities(std::vector> & existence_vectors) const; + private: std::map tracker_map_; std::list> list_tracker_; + const size_t channel_size_; // parameters float max_elapsed_time_; // [s] @@ -73,7 +75,7 @@ class TrackerProcessor 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; + const geometry_msgs::msg::Transform & self_transform, const uint & channel_index) const; }; #endif // MULTI_OBJECT_TRACKER__PROCESSOR__PROCESSOR_HPP_ diff --git a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/bicycle_tracker.hpp b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/bicycle_tracker.hpp index 2d69334a2f43f..ead0d8dbf0e5a 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/bicycle_tracker.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/bicycle_tracker.hpp @@ -56,7 +56,8 @@ class BicycleTracker : public Tracker public: BicycleTracker( const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform); + const geometry_msgs::msg::Transform & self_transform, const size_t channel_size, + const uint & channel_index); bool predict(const rclcpp::Time & time) override; bool measure( diff --git a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/big_vehicle_tracker.hpp b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/big_vehicle_tracker.hpp index 8d49138b94a24..3b509a3cb47d8 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/big_vehicle_tracker.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/big_vehicle_tracker.hpp @@ -61,7 +61,8 @@ class BigVehicleTracker : public Tracker public: BigVehicleTracker( const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform); + const geometry_msgs::msg::Transform & self_transform, const size_t channel_size, + const uint & channel_index); bool predict(const rclcpp::Time & time) override; bool measure( diff --git a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/multiple_vehicle_tracker.hpp b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/multiple_vehicle_tracker.hpp index 5722566b4a633..fef8caaf20d8a 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/multiple_vehicle_tracker.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/multiple_vehicle_tracker.hpp @@ -35,7 +35,8 @@ class MultipleVehicleTracker : public Tracker public: MultipleVehicleTracker( const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform); + const geometry_msgs::msg::Transform & self_transform, const size_t channel_size, + const uint & channel_index); bool predict(const rclcpp::Time & time) override; bool measure( diff --git a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp index 6ab7e63bce167..b7810d2471416 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp @@ -61,7 +61,8 @@ class NormalVehicleTracker : public Tracker public: NormalVehicleTracker( const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform); + const geometry_msgs::msg::Transform & self_transform, const size_t channel_size, + const uint & channel_index); bool predict(const rclcpp::Time & time) override; bool measure( diff --git a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/pass_through_tracker.hpp b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/pass_through_tracker.hpp index 48a8702d182a0..0f892098a373a 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/pass_through_tracker.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/pass_through_tracker.hpp @@ -34,7 +34,8 @@ class PassThroughTracker : public Tracker public: PassThroughTracker( const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform); + const geometry_msgs::msg::Transform & self_transform, const size_t channel_size, + const uint & channel_index); bool predict(const rclcpp::Time & time) override; bool measure( const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, diff --git a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/pedestrian_and_bicycle_tracker.hpp b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/pedestrian_and_bicycle_tracker.hpp index cf6a82088c7b6..490f6d93c6f6a 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/pedestrian_and_bicycle_tracker.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/pedestrian_and_bicycle_tracker.hpp @@ -34,7 +34,8 @@ class PedestrianAndBicycleTracker : public Tracker public: PedestrianAndBicycleTracker( const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform); + const geometry_msgs::msg::Transform & self_transform, const size_t channel_size, + const uint & channel_index); bool predict(const rclcpp::Time & time) override; bool measure( diff --git a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/pedestrian_tracker.hpp b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/pedestrian_tracker.hpp index a56250390e34f..72f5a5a002f0f 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/pedestrian_tracker.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/pedestrian_tracker.hpp @@ -64,7 +64,8 @@ class PedestrianTracker : public Tracker public: PedestrianTracker( const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform); + const geometry_msgs::msg::Transform & self_transform, const size_t channel_size, + const uint & channel_index); bool predict(const rclcpp::Time & time) override; bool measure( diff --git a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/tracker_base.hpp b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/tracker_base.hpp index ab6a747288d4a..348ba1f5d7383 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/tracker_base.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/tracker_base.hpp @@ -35,33 +35,41 @@ class Tracker { -protected: - unique_identifier_msgs::msg::UUID getUUID() const { return uuid_; } - void setClassification( - const std::vector & classification) - { - classification_ = classification; - } - void updateClassification( - const std::vector & classification); - private: unique_identifier_msgs::msg::UUID uuid_; + + // classification std::vector classification_; + + // existence states int no_measurement_count_; int total_no_measurement_count_; int total_measurement_count_; rclcpp::Time last_update_with_measurement_time_; + std::vector existence_probabilities_; + float total_existence_probability_; public: Tracker( const rclcpp::Time & time, - const std::vector & classification); + const std::vector & classification, + const size_t & channel_size); virtual ~Tracker() {} + + void initializeExistenceProbabilities( + const uint & channel_index, const float & existence_probability); + bool getExistenceProbabilityVector(std::vector & existence_vector) const + { + existence_vector = existence_probabilities_; + return existence_vector.size() > 0; + } bool updateWithMeasurement( const autoware_auto_perception_msgs::msg::DetectedObject & object, - const rclcpp::Time & measurement_time, const geometry_msgs::msg::Transform & self_transform); - bool updateWithoutMeasurement(); + const rclcpp::Time & measurement_time, const geometry_msgs::msg::Transform & self_transform, + const uint & channel_index); + bool updateWithoutMeasurement(const rclcpp::Time & now); + + // classification std::vector getClassification() const { return classification_; @@ -70,6 +78,8 @@ class Tracker { return object_recognition_utils::getHighestProbLabel(classification_); } + + // existence states int getNoMeasurementCount() const { return no_measurement_count_; } int getTotalNoMeasurementCount() const { return total_no_measurement_count_; } int getTotalMeasurementCount() const { return total_measurement_count_; } @@ -77,13 +87,22 @@ class Tracker { return (current_time - last_update_with_measurement_time_).seconds(); } + +protected: + unique_identifier_msgs::msg::UUID getUUID() const { return uuid_; } + void setClassification( + const std::vector & classification) + { + classification_ = classification; + } + void updateClassification( + const std::vector & classification); + + // virtual functions +public: virtual geometry_msgs::msg::PoseWithCovariance getPoseWithCovariance( const rclcpp::Time & time) const; - /* - * Pure virtual function - */ - protected: virtual bool measure( const autoware_auto_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, diff --git a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/unknown_tracker.hpp b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/unknown_tracker.hpp index 73bf7849e13d8..3ef58773b408f 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/unknown_tracker.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/tracker/model/unknown_tracker.hpp @@ -49,7 +49,8 @@ class UnknownTracker : public Tracker public: UnknownTracker( const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform); + const geometry_msgs::msg::Transform & self_transform, const size_t channel_size, + const uint & channel_index); bool predict(const rclcpp::Time & time) override; bool measure( diff --git a/perception/multi_object_tracker/include/multi_object_tracker/utils/utils.hpp b/perception/multi_object_tracker/include/multi_object_tracker/utils/utils.hpp index b19b0ba7ee10c..5842246bc1313 100644 --- a/perception/multi_object_tracker/include/multi_object_tracker/utils/utils.hpp +++ b/perception/multi_object_tracker/include/multi_object_tracker/utils/utils.hpp @@ -295,40 +295,43 @@ inline void calcAnchorPointOffset( * @param input_object: input convex hull objects * @param output_object: output bounding box objects */ -inline void convertConvexHullToBoundingBox( +inline bool convertConvexHullToBoundingBox( const autoware_auto_perception_msgs::msg::DetectedObject & input_object, autoware_auto_perception_msgs::msg::DetectedObject & output_object) { - const Eigen::Vector2d center{ - input_object.kinematics.pose_with_covariance.pose.position.x, - input_object.kinematics.pose_with_covariance.pose.position.y}; - const auto yaw = tf2::getYaw(input_object.kinematics.pose_with_covariance.pose.orientation); - const Eigen::Matrix2d R_inv = Eigen::Rotation2Dd(-yaw).toRotationMatrix(); + // check footprint size + if (input_object.shape.footprint.points.size() < 3) { + return false; + } + // look for bounding box boundary double max_x = 0; double max_y = 0; double min_x = 0; double min_y = 0; double max_z = 0; - - // look for bounding box boundary for (size_t i = 0; i < input_object.shape.footprint.points.size(); ++i) { - Eigen::Vector2d vertex{ - input_object.shape.footprint.points.at(i).x, input_object.shape.footprint.points.at(i).y}; - - const Eigen::Vector2d local_vertex = R_inv * (vertex - center); - max_x = std::max(max_x, local_vertex.x()); - max_y = std::max(max_y, local_vertex.y()); - min_x = std::min(min_x, local_vertex.x()); - min_y = std::min(min_y, local_vertex.y()); - - max_z = std::max(max_z, static_cast(input_object.shape.footprint.points.at(i).z)); + const double foot_x = input_object.shape.footprint.points.at(i).x; + const double foot_y = input_object.shape.footprint.points.at(i).y; + const double foot_z = input_object.shape.footprint.points.at(i).z; + max_x = std::max(max_x, foot_x); + max_y = std::max(max_y, foot_y); + min_x = std::min(min_x, foot_x); + min_y = std::min(min_y, foot_y); + max_z = std::max(max_z, foot_z); } // calc bounding box state const double length = max_x - min_x; const double width = max_y - min_y; const double height = max_z; + + // calc new center + const Eigen::Vector2d center{ + input_object.kinematics.pose_with_covariance.pose.position.x, + input_object.kinematics.pose_with_covariance.pose.position.y}; + const auto yaw = tf2::getYaw(input_object.kinematics.pose_with_covariance.pose.orientation); + const Eigen::Matrix2d R_inv = Eigen::Rotation2Dd(-yaw).toRotationMatrix(); const Eigen::Vector2d new_local_center{(max_x + min_x) / 2.0, (max_y + min_y) / 2.0}; const Eigen::Vector2d new_center = center + R_inv.transpose() * new_local_center; @@ -341,6 +344,8 @@ inline void convertConvexHullToBoundingBox( output_object.shape.dimensions.x = length; output_object.shape.dimensions.y = width; output_object.shape.dimensions.z = height; + + return true; } inline bool getMeasurementYaw( diff --git a/perception/multi_object_tracker/launch/multi_object_tracker.launch.xml b/perception/multi_object_tracker/launch/multi_object_tracker.launch.xml index dcd080b851c20..b00ccd8fa623e 100644 --- a/perception/multi_object_tracker/launch/multi_object_tracker.launch.xml +++ b/perception/multi_object_tracker/launch/multi_object_tracker.launch.xml @@ -1,14 +1,16 @@ - + + - - + + + 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/debugger/debug_object.cpp b/perception/multi_object_tracker/src/debugger/debug_object.cpp new file mode 100644 index 0000000000000..ebbeab43a155b --- /dev/null +++ b/perception/multi_object_tracker/src/debugger/debug_object.cpp @@ -0,0 +1,389 @@ +// 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/debugger/debug_object.hpp" + +#include "autoware_auto_perception_msgs/msg/tracked_object.hpp" + +#include + +#include +#include +#include +#include + +namespace +{ +std::string uuidToString(const unique_identifier_msgs::msg::UUID & uuid_msg) +{ + std::stringstream ss; + for (auto i = 0; i < 16; ++i) { + ss << std::hex << std::setfill('0') << std::setw(2) << +uuid_msg.uuid[i]; + } + return ss.str(); +} + +boost::uuids::uuid uuidToBoostUuid(const unique_identifier_msgs::msg::UUID & uuid_msg) +{ + const std::string uuid_str = uuidToString(uuid_msg); + boost::uuids::string_generator gen; + boost::uuids::uuid uuid = gen(uuid_str); + return uuid; +} + +int32_t uuidToInt(const boost::uuids::uuid & uuid) +{ + return boost::uuids::hash_value(uuid); +} +} // namespace + +TrackerObjectDebugger::TrackerObjectDebugger(std::string frame_id) +{ + // set frame id + frame_id_ = frame_id; + + // initialize markers + markers_.markers.clear(); + current_ids_.clear(); + previous_ids_.clear(); + message_time_ = rclcpp::Time(0, 0); +} + +void TrackerObjectDebugger::reset() +{ + // maintain previous ids + previous_ids_.clear(); + previous_ids_ = current_ids_; + current_ids_.clear(); + + // clear markers, object data list + object_data_list_.clear(); + markers_.markers.clear(); +} + +void TrackerObjectDebugger::collect( + const rclcpp::Time & message_time, const std::list> & list_tracker, + const uint & channel_index, + const autoware_auto_perception_msgs::msg::DetectedObjects & detected_objects, + const std::unordered_map & direct_assignment, + const std::unordered_map & /*reverse_assignment*/) +{ + if (!is_initialized_) is_initialized_ = true; + + message_time_ = message_time; + + int tracker_idx = 0; + for (auto tracker_itr = list_tracker.begin(); tracker_itr != list_tracker.end(); + ++tracker_itr, ++tracker_idx) { + ObjectData object_data; + object_data.time = message_time; + object_data.channel_id = channel_index; + + autoware_auto_perception_msgs::msg::TrackedObject tracked_object; + (*(tracker_itr))->getTrackedObject(message_time, tracked_object); + object_data.uuid = uuidToBoostUuid(tracked_object.object_id); + object_data.uuid_int = uuidToInt(object_data.uuid); + object_data.uuid_str = uuidToString(tracked_object.object_id); + + // tracker + bool is_associated = false; + geometry_msgs::msg::Point tracker_point, detection_point; + tracker_point.x = tracked_object.kinematics.pose_with_covariance.pose.position.x; + tracker_point.y = tracked_object.kinematics.pose_with_covariance.pose.position.y; + tracker_point.z = tracked_object.kinematics.pose_with_covariance.pose.position.z; + + // detection + if (direct_assignment.find(tracker_idx) != direct_assignment.end()) { + const auto & associated_object = + detected_objects.objects.at(direct_assignment.find(tracker_idx)->second); + detection_point.x = associated_object.kinematics.pose_with_covariance.pose.position.x; + detection_point.y = associated_object.kinematics.pose_with_covariance.pose.position.y; + detection_point.z = associated_object.kinematics.pose_with_covariance.pose.position.z; + is_associated = true; + } else { + detection_point.x = tracker_point.x; + detection_point.y = tracker_point.y; + detection_point.z = tracker_point.z; + } + + object_data.tracker_point = tracker_point; + object_data.detection_point = detection_point; + object_data.is_associated = is_associated; + + // existence probabilities + std::vector existence_vector; + (*(tracker_itr))->getExistenceProbabilityVector(existence_vector); + object_data.existence_vector = existence_vector; + + object_data_list_.push_back(object_data); + } +} + +void TrackerObjectDebugger::process() +{ + if (!is_initialized_) return; + + // update uuid_int + for (auto & object_data : object_data_list_) { + current_ids_.insert(object_data.uuid_int); + } + + // sort by uuid, collect the same uuid object_data as a group, and loop for the groups + object_data_groups_.clear(); + { + // sort by uuid + std::sort( + object_data_list_.begin(), object_data_list_.end(), + [](const ObjectData & a, const ObjectData & b) { return a.uuid < b.uuid; }); + + // collect the same uuid object_data as a group + std::vector object_data_group; + boost::uuids::uuid previous_uuid = object_data_list_.front().uuid; + for (const auto & object_data : object_data_list_) { + // if the uuid is different, push the group and clear the group + if (object_data.uuid != previous_uuid) { + // push the group + object_data_groups_.push_back(object_data_group); + object_data_group.clear(); + previous_uuid = object_data.uuid; + } + // push the object_data to the group + object_data_group.push_back(object_data); + } + // push the last group + object_data_groups_.push_back(object_data_group); + } +} + +void TrackerObjectDebugger::draw( + const std::vector> object_data_groups, + visualization_msgs::msg::MarkerArray & marker_array) const +{ + // initialize markers + marker_array.markers.clear(); + + constexpr int PALETTE_SIZE = 16; + constexpr std::array, PALETTE_SIZE> color_array = {{ + {{0.0, 0.0, 1.0}}, // Blue + {{0.0, 1.0, 0.0}}, // Green + {{1.0, 1.0, 0.0}}, // Yellow + {{1.0, 0.0, 0.0}}, // Red + {{0.0, 1.0, 1.0}}, // Cyan + {{1.0, 0.0, 1.0}}, // Magenta + {{1.0, 0.64, 0.0}}, // Orange + {{0.75, 1.0, 0.0}}, // Lime + {{0.0, 0.5, 0.5}}, // Teal + {{0.5, 0.0, 0.5}}, // Purple + {{1.0, 0.75, 0.8}}, // Pink + {{0.65, 0.17, 0.17}}, // Brown + {{0.5, 0.0, 0.0}}, // Maroon + {{0.5, 0.5, 0.0}}, // Olive + {{0.0, 0.0, 0.5}}, // Navy + {{0.5, 0.5, 0.5}} // Grey + }}; + + for (const auto & object_data_group : object_data_groups) { + if (object_data_group.empty()) continue; + const auto object_data_front = object_data_group.front(); + const auto object_data_back = object_data_group.back(); + + // set a reference marker + visualization_msgs::msg::Marker marker; + marker.header.frame_id = frame_id_; + marker.header.stamp = object_data_front.time; + marker.id = object_data_front.uuid_int; + marker.pose.position.x = 0; + marker.pose.position.y = 0; + marker.pose.position.z = 0; + marker.color.a = 1.0; + marker.color.r = 1.0; + marker.color.g = 1.0; + marker.color.b = 1.0; // white + marker.lifetime = rclcpp::Duration::from_seconds(0); + + // get marker - existence_probability + visualization_msgs::msg::Marker text_marker; + text_marker = marker; + text_marker.ns = "existence_probability"; + text_marker.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; + text_marker.action = visualization_msgs::msg::Marker::ADD; + text_marker.pose.position.z += 1.8; + text_marker.scale.z = 0.5; + text_marker.pose.position.x = object_data_front.tracker_point.x; + text_marker.pose.position.y = object_data_front.tracker_point.y; + text_marker.pose.position.z = object_data_front.tracker_point.z + 2.5; + + // show the last existence probability + // print existence probability with channel name + // probability to text, two digits of percentage + std::string existence_probability_text = ""; + for (size_t i = 0; i < object_data_front.existence_vector.size(); ++i) { + std::stringstream stream; + stream << std::fixed << std::setprecision(0) << object_data_front.existence_vector[i] * 100; + existence_probability_text += channel_names_[i] + stream.str() + ":"; + } + existence_probability_text = + existence_probability_text.substr(0, existence_probability_text.size() - 1); + existence_probability_text += "\n" + object_data_front.uuid_str.substr(0, 6); + + text_marker.text = existence_probability_text; + marker_array.markers.push_back(text_marker); + + // loop for each object_data in the group + // boxed to tracker positions + // and link lines to the detected positions + const double marker_height_offset = 1.0; + const double assign_height_offset = 0.6; + + visualization_msgs::msg::Marker marker_track_boxes; + marker_track_boxes = marker; + marker_track_boxes.ns = "track_boxes"; + marker_track_boxes.type = visualization_msgs::msg::Marker::CUBE_LIST; + marker_track_boxes.action = visualization_msgs::msg::Marker::ADD; + marker_track_boxes.scale.x = 0.4; + marker_track_boxes.scale.y = 0.4; + marker_track_boxes.scale.z = 0.4; + + // make detected object markers per channel + std::vector marker_detect_boxes_per_channel; + std::vector marker_detect_lines_per_channel; + + for (size_t idx = 0; idx < channel_names_.size(); idx++) { + // get color - by channel index + std_msgs::msg::ColorRGBA color; + color.a = 1.0; + color.r = color_array[idx % PALETTE_SIZE][0]; + color.g = color_array[idx % PALETTE_SIZE][1]; + color.b = color_array[idx % PALETTE_SIZE][2]; + + visualization_msgs::msg::Marker marker_detect_boxes; + marker_detect_boxes = marker; + marker_detect_boxes.ns = "detect_boxes_" + channel_names_[idx]; + marker_detect_boxes.type = visualization_msgs::msg::Marker::CUBE_LIST; + marker_detect_boxes.action = visualization_msgs::msg::Marker::ADD; + marker_detect_boxes.scale.x = 0.2; + marker_detect_boxes.scale.y = 0.2; + marker_detect_boxes.scale.z = 0.2; + marker_detect_boxes.color = color; + marker_detect_boxes_per_channel.push_back(marker_detect_boxes); + + visualization_msgs::msg::Marker marker_lines; + marker_lines = marker; + marker_lines.ns = "association_lines_" + channel_names_[idx]; + marker_lines.type = visualization_msgs::msg::Marker::LINE_LIST; + marker_lines.action = visualization_msgs::msg::Marker::ADD; + marker_lines.scale.x = 0.15; + marker_lines.points.clear(); + marker_lines.color = color; + marker_detect_lines_per_channel.push_back(marker_lines); + } + + bool is_any_associated = false; + + for (const auto & object_data : object_data_group) { + int channel_id = object_data.channel_id; + + // set box + geometry_msgs::msg::Point box_point; + box_point.x = object_data.tracker_point.x; + box_point.y = object_data.tracker_point.y; + box_point.z = object_data.tracker_point.z + marker_height_offset; + marker_track_boxes.points.push_back(box_point); + + // set association marker, if exists + if (!object_data.is_associated) continue; + is_any_associated = true; + + // associated object box + visualization_msgs::msg::Marker & marker_detect_boxes = + marker_detect_boxes_per_channel.at(channel_id); + box_point.x = object_data.detection_point.x; + box_point.y = object_data.detection_point.y; + box_point.z = object_data.detection_point.z + marker_height_offset + assign_height_offset; + marker_detect_boxes.points.push_back(box_point); + + // association line + visualization_msgs::msg::Marker & marker_lines = + marker_detect_lines_per_channel.at(channel_id); + geometry_msgs::msg::Point line_point; + line_point.x = object_data.tracker_point.x; + line_point.y = object_data.tracker_point.y; + line_point.z = object_data.tracker_point.z + marker_height_offset; + marker_lines.points.push_back(line_point); + line_point.x = object_data.detection_point.x; + line_point.y = object_data.detection_point.y; + line_point.z = object_data.detection_point.z + marker_height_offset + assign_height_offset; + marker_lines.points.push_back(line_point); + } + + // add markers + marker_array.markers.push_back(marker_track_boxes); + if (is_any_associated) { + for (size_t i = 0; i < channel_names_.size(); i++) { + if (marker_detect_boxes_per_channel.at(i).points.empty()) continue; + marker_array.markers.push_back(marker_detect_boxes_per_channel.at(i)); + } + for (size_t i = 0; i < channel_names_.size(); i++) { + if (marker_detect_lines_per_channel.at(i).points.empty()) continue; + marker_array.markers.push_back(marker_detect_lines_per_channel.at(i)); + } + } else { + for (size_t i = 0; i < channel_names_.size(); i++) { + marker_detect_boxes_per_channel.at(i).action = visualization_msgs::msg::Marker::DELETE; + marker_array.markers.push_back(marker_detect_boxes_per_channel.at(i)); + } + for (size_t i = 0; i < channel_names_.size(); i++) { + marker_detect_lines_per_channel.at(i).action = visualization_msgs::msg::Marker::DELETE; + marker_array.markers.push_back(marker_detect_lines_per_channel.at(i)); + } + } + } + + return; +} + +void TrackerObjectDebugger::getMessage(visualization_msgs::msg::MarkerArray & marker_array) const +{ + if (!is_initialized_) return; + + // draw markers + draw(object_data_groups_, marker_array); + + // remove old markers + for (const auto & previous_id : previous_ids_) { + if (current_ids_.find(previous_id) != current_ids_.end()) { + continue; + } + + visualization_msgs::msg::Marker delete_marker; + delete_marker.header.frame_id = frame_id_; + delete_marker.header.stamp = message_time_; + delete_marker.ns = "existence_probability"; + delete_marker.id = previous_id; + delete_marker.action = visualization_msgs::msg::Marker::DELETE; + marker_array.markers.push_back(delete_marker); + + delete_marker.ns = "track_boxes"; + marker_array.markers.push_back(delete_marker); + + for (size_t idx = 0; idx < channel_names_.size(); idx++) { + delete_marker.ns = "detect_boxes_" + channel_names_[idx]; + marker_array.markers.push_back(delete_marker); + delete_marker.ns = "association_lines_" + channel_names_[idx]; + marker_array.markers.push_back(delete_marker); + } + } + + return; +} diff --git a/perception/multi_object_tracker/src/debugger.cpp b/perception/multi_object_tracker/src/debugger/debugger.cpp similarity index 79% rename from perception/multi_object_tracker/src/debugger.cpp rename to perception/multi_object_tracker/src/debugger/debugger.cpp index b5632a13e78fc..afb0ecdc22996 100644 --- a/perception/multi_object_tracker/src/debugger.cpp +++ b/perception/multi_object_tracker/src/debugger/debugger.cpp @@ -1,4 +1,4 @@ -// Copyright 2024 Tier IV, Inc. +// 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. @@ -11,14 +11,13 @@ // 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/debugger.hpp" +#include "multi_object_tracker/debugger/debugger.hpp" #include -TrackerDebugger::TrackerDebugger(rclcpp::Node & node) : diagnostic_updater_(&node), node_(node) +TrackerDebugger::TrackerDebugger(rclcpp::Node & node, const std::string & frame_id) +: node_(node), diagnostic_updater_(&node), object_debugger_(frame_id) { // declare debug parameters to decide whether to publish debug topics loadParameters(); @@ -31,7 +30,12 @@ TrackerDebugger::TrackerDebugger(rclcpp::Node & node) : diagnostic_updater_(&nod if (debug_settings_.publish_tentative_objects) { debug_tentative_objects_pub_ = node_.create_publisher( - "debug/tentative_objects", rclcpp::QoS{1}); + "~/debug/tentative_objects", rclcpp::QoS{1}); + } + + if (debug_settings_.publish_debug_markers) { + debug_objects_markers_pub_ = node_.create_publisher( + "~/debug/objects_markers", rclcpp::QoS{1}); } // initialize timestamps @@ -46,14 +50,6 @@ TrackerDebugger::TrackerDebugger(rclcpp::Node & node) : diagnostic_updater_(&nod setupDiagnostics(); } -void TrackerDebugger::setupDiagnostics() -{ - diagnostic_updater_.setHardwareID(node_.get_name()); - diagnostic_updater_.add( - "Perception delay check from original header stamp", this, &TrackerDebugger::checkDelay); - diagnostic_updater_.setPeriod(0.1); -} - void TrackerDebugger::loadParameters() { try { @@ -61,6 +57,7 @@ void TrackerDebugger::loadParameters() node_.declare_parameter("publish_processing_time"); debug_settings_.publish_tentative_objects = node_.declare_parameter("publish_tentative_objects"); + debug_settings_.publish_debug_markers = node_.declare_parameter("publish_debug_markers"); debug_settings_.diagnostics_warn_delay = node_.declare_parameter("diagnostics_warn_delay"); debug_settings_.diagnostics_error_delay = @@ -69,11 +66,32 @@ void TrackerDebugger::loadParameters() RCLCPP_WARN(node_.get_logger(), "Failed to declare parameter: %s", e.what()); debug_settings_.publish_processing_time = false; debug_settings_.publish_tentative_objects = false; + debug_settings_.publish_debug_markers = false; debug_settings_.diagnostics_warn_delay = 0.5; debug_settings_.diagnostics_error_delay = 1.0; } } +void TrackerDebugger::setupDiagnostics() +{ + diagnostic_updater_.setHardwareID(node_.get_name()); + diagnostic_updater_.add( + "Perception delay check from original header stamp", this, &TrackerDebugger::checkDelay); + diagnostic_updater_.setPeriod(0.1); +} + +// Object publishing functions + +void TrackerDebugger::publishTentativeObjects( + const autoware_auto_perception_msgs::msg::TrackedObjects & tentative_objects) const +{ + if (debug_settings_.publish_tentative_objects) { + debug_tentative_objects_pub_->publish(tentative_objects); + } +} + +// Time measurement functions + void TrackerDebugger::checkDelay(diagnostic_updater::DiagnosticStatusWrapper & stat) { if (!is_initialized_) { @@ -97,14 +115,6 @@ void TrackerDebugger::checkDelay(diagnostic_updater::DiagnosticStatusWrapper & s stat.add("Detection delay", delay); } -void TrackerDebugger::publishTentativeObjects( - const autoware_auto_perception_msgs::msg::TrackedObjects & tentative_objects) const -{ - if (debug_settings_.publish_tentative_objects) { - debug_tentative_objects_pub_->publish(tentative_objects); - } -} - void TrackerDebugger::startMeasurementTime( const rclcpp::Time & now, const rclcpp::Time & measurement_header_stamp) { @@ -167,3 +177,33 @@ void TrackerDebugger::endPublishTime(const rclcpp::Time & now, const rclcpp::Tim } stamp_publish_output_ = now; } + +void TrackerDebugger::collectObjectInfo( + const rclcpp::Time & message_time, const std::list> & list_tracker, + const uint & channel_index, + const autoware_auto_perception_msgs::msg::DetectedObjects & detected_objects, + const std::unordered_map & direct_assignment, + const std::unordered_map & reverse_assignment) +{ + if (!debug_settings_.publish_debug_markers) return; + object_debugger_.collect( + message_time, list_tracker, channel_index, detected_objects, direct_assignment, + reverse_assignment); +} + +// ObjectDebugger +void TrackerDebugger::publishObjectsMarkers() +{ + if (!debug_settings_.publish_debug_markers) return; + + visualization_msgs::msg::MarkerArray marker_message; + // process data + object_debugger_.process(); + + // publish markers + object_debugger_.getMessage(marker_message); + debug_objects_markers_pub_->publish(marker_message); + + // reset object data + object_debugger_.reset(); +} 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 d80a21813b28b..54c23d39f5357 100644 --- a/perception/multi_object_tracker/src/multi_object_tracker_core.cpp +++ b/perception/multi_object_tracker/src/multi_object_tracker_core.cpp @@ -36,8 +36,6 @@ #include #include -using Label = autoware_auto_perception_msgs::msg::ObjectClassification; - namespace { // Function to get the transform between two frames @@ -67,24 +65,85 @@ boost::optional getTransformAnonymous( } // namespace +namespace multi_object_tracker +{ +using Label = autoware_auto_perception_msgs::msg::ObjectClassification; + MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) : rclcpp::Node("multi_object_tracker", node_options), tf_buffer_(this->get_clock()), tf_listener_(tf_buffer_), last_published_time_(this->now()) { - // Create publishers and subscribers - detected_object_sub_ = create_subscription( - "input", rclcpp::QoS{1}, - std::bind(&MultiObjectTracker::onMeasurement, this, std::placeholders::_1)); - tracked_objects_pub_ = - create_publisher("output", rclcpp::QoS{1}); + // glog for debug + if (!google::IsGoogleLoggingInitialized()) { + google::InitGoogleLogging("multi_object_tracker"); + google::InstallFailureSignalHandler(); + } // 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")}; + declare_parameter("selected_input_channels", std::vector()); + std::vector selected_input_channels = + get_parameter("selected_input_channels").as_string_array(); + + // ROS interface - Publisher + tracked_objects_pub_ = create_publisher("output", rclcpp::QoS{1}); + + // ROS interface - Input channels + // Get input channels + std::vector input_topic_names; + std::vector input_names_long; + std::vector input_names_short; + std::vector input_is_spawn_enabled; + + if (selected_input_channels.empty()) { + RCLCPP_ERROR(this->get_logger(), "No input topics are specified."); + return; + } + + for (const auto & selected_input_channel : selected_input_channels) { + // required parameters, no default value + const std::string input_topic_name = + declare_parameter("input_channels." + selected_input_channel + ".topic"); + input_topic_names.push_back(input_topic_name); + + // required parameter, but can set a default value + const bool spawn_enabled = declare_parameter( + "input_channels." + selected_input_channel + ".can_spawn_new_tracker", true); + input_is_spawn_enabled.push_back(spawn_enabled); + + // optional parameters + const std::string default_name = selected_input_channel; + const std::string name_long = declare_parameter( + "input_channels." + selected_input_channel + ".optional.name", default_name); + input_names_long.push_back(name_long); + + const std::string default_name_short = selected_input_channel.substr(0, 3); + const std::string name_short = declare_parameter( + "input_channels." + selected_input_channel + ".optional.short_name", default_name_short); + input_names_short.push_back(name_short); + } + + input_channel_size_ = input_topic_names.size(); + input_channels_.resize(input_channel_size_); + + for (size_t i = 0; i < input_channel_size_; i++) { + input_channels_[i].input_topic = input_topic_names[i]; + input_channels_[i].long_name = input_names_long[i]; + input_channels_[i].short_name = input_names_short[i]; + input_channels_[i].is_spawn_enabled = input_is_spawn_enabled[i]; + } + + // Initialize input manager + input_manager_ = std::make_unique(*this); + input_manager_->init(input_channels_); // Initialize input manager, set subscriptions + input_manager_->setTriggerFunction( + std::bind(&MultiObjectTracker::onTrigger, this)); // Set trigger function + // Create tf timer auto cti = std::make_shared( this->get_node_base_interface(), this->get_node_timers_interface()); @@ -119,7 +178,7 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) tracker_map.insert(std::make_pair( Label::MOTORCYCLE, this->declare_parameter("motorcycle_tracker"))); - processor_ = std::make_unique(tracker_map); + processor_ = std::make_unique(tracker_map, input_channel_size_); } // Data association initialization @@ -138,35 +197,96 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) } // Debugger - debugger_ = std::make_unique(*this); + debugger_ = std::make_unique(*this, world_frame_id_); + debugger_->setObjectChannels(input_names_short); published_time_publisher_ = std::make_unique(this); } -void MultiObjectTracker::onMeasurement( - const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr input_objects_msg) +void MultiObjectTracker::onTrigger() +{ + const rclcpp::Time current_time = this->now(); + // get objects from the input manager and run process + std::vector> objects_list; + const bool is_objects_ready = input_manager_->getObjects(current_time, objects_list); + if (!is_objects_ready) return; + + onMessage(objects_list); + const rclcpp::Time latest_time(objects_list.back().second.header.stamp); + + // Publish objects if the timer is not enabled + if (publish_timer_ == nullptr) { + // if the delay compensation is disabled, publish the objects in the latest time + publish(latest_time); + } else { + // Publish if the next publish time is close + const double minimum_publish_interval = publisher_period_ * 0.70; // 70% of the period + if ((current_time - last_published_time_).seconds() > minimum_publish_interval) { + checkAndPublish(current_time); + } + } +} + +void MultiObjectTracker::onTimer() +{ + const rclcpp::Time current_time = this->now(); + + // 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) return; + + // get objects from the input manager and run process + ObjectsList objects_list; + const bool is_objects_ready = input_manager_->getObjects(current_time, objects_list); + if (is_objects_ready) { + onMessage(objects_list); + } + + // Publish + checkAndPublish(current_time); +} + +void MultiObjectTracker::onMessage(const ObjectsList & objects_list) +{ + const rclcpp::Time current_time = this->now(); + const rclcpp::Time oldest_time(objects_list.front().second.header.stamp); + + // process start + debugger_->startMeasurementTime(this->now(), oldest_time); + // run process for each DetectedObjects + for (const auto & objects_data : objects_list) { + runProcess(objects_data.second, objects_data.first); + } + // process end + debugger_->endMeasurementTime(this->now()); +} + +void MultiObjectTracker::runProcess( + const DetectedObjects & input_objects_msg, const uint & channel_index) { // Get the time of the measurement const rclcpp::Time measurement_time = - rclcpp::Time(input_objects_msg->header.stamp, this->now().get_clock_type()); + rclcpp::Time(input_objects_msg.header.stamp, this->now().get_clock_type()); - /* keep the latest input stamp and check transform*/ - debugger_->startMeasurementTime(this->now(), measurement_time); + // Get the transform of the self frame const auto self_transform = getTransformAnonymous(tf_buffer_, "base_link", world_frame_id_, measurement_time); if (!self_transform) { return; } - /* transform to world coordinate */ - autoware_auto_perception_msgs::msg::DetectedObjects transformed_objects; + + // Transform the objects to the world frame + DetectedObjects transformed_objects; if (!object_recognition_utils::transformObjects( - *input_objects_msg, world_frame_id_, tf_buffer_, transformed_objects)) { + input_objects_msg, world_frame_id_, tf_buffer_, transformed_objects)) { return; } - ////// Tracker Process - //// Associate and update /* prediction */ processor_->predict(measurement_time); + /* object association */ std::unordered_map direct_assignment, reverse_assignment; { @@ -176,40 +296,22 @@ void MultiObjectTracker::onMeasurement( Eigen::MatrixXd score_matrix = data_association_->calcScoreMatrix( detected_objects, list_tracker); // row : tracker, col : measurement data_association_->assign(score_matrix, direct_assignment, reverse_assignment); + + // Collect debug information - tracker list, existence probabilities, association results + debugger_->collectObjectInfo( + measurement_time, processor_->getListTracker(), channel_index, transformed_objects, + direct_assignment, reverse_assignment); } + /* tracker update */ - processor_->update(transformed_objects, *self_transform, direct_assignment); + processor_->update(transformed_objects, *self_transform, direct_assignment, channel_index); + /* tracker pruning */ processor_->prune(measurement_time); - /* spawn new tracker */ - processor_->spawn(transformed_objects, *self_transform, reverse_assignment); - - // debugger time - debugger_->endMeasurementTime(this->now()); - - // 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()); - } - } -} -void MultiObjectTracker::onTimer() -{ - const rclcpp::Time current_time = this->now(); - // 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); + /* spawn new tracker */ + if (input_manager_->isChannelSpawnEnabled(channel_index)) { + processor_->spawn(transformed_objects, *self_transform, reverse_assignment, channel_index); } } @@ -234,7 +336,7 @@ void MultiObjectTracker::publish(const rclcpp::Time & time) const return; } // Create output msg - autoware_auto_perception_msgs::msg::TrackedObjects output_msg, tentative_objects_msg; + TrackedObjects output_msg, tentative_objects_msg; output_msg.header.frame_id = world_frame_id_; processor_->getTrackedObjects(time, output_msg); @@ -246,11 +348,14 @@ void MultiObjectTracker::publish(const rclcpp::Time & time) const debugger_->endPublishTime(this->now(), time); if (debugger_->shouldPublishTentativeObjects()) { - autoware_auto_perception_msgs::msg::TrackedObjects tentative_objects_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); } + debugger_->publishObjectsMarkers(); } -RCLCPP_COMPONENTS_REGISTER_NODE(MultiObjectTracker) +} // namespace multi_object_tracker + +RCLCPP_COMPONENTS_REGISTER_NODE(multi_object_tracker::MultiObjectTracker) diff --git a/perception/multi_object_tracker/src/multi_object_tracker_node.cpp b/perception/multi_object_tracker/src/multi_object_tracker_node.cpp deleted file mode 100644 index f20aedf16efef..0000000000000 --- a/perception/multi_object_tracker/src/multi_object_tracker_node.cpp +++ /dev/null @@ -1,34 +0,0 @@ -// 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; -} diff --git a/perception/multi_object_tracker/src/processor/input_manager.cpp b/perception/multi_object_tracker/src/processor/input_manager.cpp new file mode 100644 index 0000000000000..44bdf09046ccd --- /dev/null +++ b/perception/multi_object_tracker/src/processor/input_manager.cpp @@ -0,0 +1,371 @@ +// 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/input_manager.hpp" + +#include + +namespace multi_object_tracker +{ +/////////////////////////// +/////// InputStream /////// +/////////////////////////// +InputStream::InputStream(rclcpp::Node & node, uint & index) : node_(node), index_(index) +{ +} + +void InputStream::init(const InputChannel & input_channel) +{ + // Initialize parameters + input_topic_ = input_channel.input_topic; + long_name_ = input_channel.long_name; + short_name_ = input_channel.short_name; + is_spawn_enabled_ = input_channel.is_spawn_enabled; + + // Initialize queue + objects_que_.clear(); + + // Initialize latency statistics + latency_mean_ = 0.2; // [s] (initial value) + latency_var_ = 0.0; + interval_mean_ = 0.0; // [s] (initial value) + interval_var_ = 0.0; + + latest_measurement_time_ = node_.now(); + latest_message_time_ = node_.now(); +} + +bool InputStream::getTimestamps( + rclcpp::Time & latest_measurement_time, rclcpp::Time & latest_message_time) const +{ + if (!isTimeInitialized()) { + return false; + } + latest_measurement_time = latest_measurement_time_; + latest_message_time = latest_message_time_; + return true; +} + +void InputStream::onMessage( + const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr msg) +{ + const DetectedObjects objects = *msg; + objects_que_.push_back(objects); + if (objects_que_.size() > que_size_) { + objects_que_.pop_front(); + } + + // update the timing statistics + rclcpp::Time now = node_.now(); + rclcpp::Time objects_time(objects.header.stamp); + updateTimingStatus(now, objects_time); + + // trigger the function if it is set + if (func_trigger_) { + func_trigger_(index_); + } +} + +void InputStream::updateTimingStatus(const rclcpp::Time & now, const rclcpp::Time & objects_time) +{ + // Define constants + constexpr int SKIP_COUNT = 4; // Skip the initial messages + constexpr int INITIALIZATION_COUNT = 16; // Initialization process count + + // Update latency statistics + // skip initial messages for the latency statistics + if (initial_count_ > SKIP_COUNT) { + const double latency = (now - objects_time).seconds(); + if (initial_count_ < INITIALIZATION_COUNT) { + // set higher gain for the initial messages + constexpr double initial_gain = 0.5; + latency_mean_ = (1.0 - initial_gain) * latency_mean_ + initial_gain * latency; + } else { + constexpr double gain = 0.05; + latency_mean_ = (1.0 - gain) * latency_mean_ + gain * latency; + const double latency_delta = latency - latency_mean_; + latency_var_ = (1.0 - gain) * latency_var_ + gain * latency_delta * latency_delta; + } + } + + // Calculate interval, Update interval statistics + if (initial_count_ > SKIP_COUNT) { + const double interval = (now - latest_message_time_).seconds(); + if (interval < 0.0) { + RCLCPP_WARN( + node_.get_logger(), + "InputManager::updateTimingStatus %s: Negative interval detected, now: %f, " + "latest_message_time_: %f", + long_name_.c_str(), now.seconds(), latest_message_time_.seconds()); + } else if (initial_count_ < INITIALIZATION_COUNT) { + // Initialization + constexpr double initial_gain = 0.5; + interval_mean_ = (1.0 - initial_gain) * interval_mean_ + initial_gain * interval; + } else { + // The interval is considered regular if it is within 0.5 and 1.5 times the mean interval + bool update_statistics = interval > 0.5 * interval_mean_ && interval < 1.5 * interval_mean_; + if (update_statistics) { + constexpr double gain = 0.05; + interval_mean_ = (1.0 - gain) * interval_mean_ + gain * interval; + const double interval_delta = interval - interval_mean_; + interval_var_ = (1.0 - gain) * interval_var_ + gain * interval_delta * interval_delta; + } + } + } + + // Update time + latest_message_time_ = now; + constexpr double delay_threshold = 3.0; // [s] + if (objects_time < latest_measurement_time_ - rclcpp::Duration::from_seconds(delay_threshold)) { + // If the given object time is older than the latest measurement time by more than the + // threshold, the system time may have been reset. Reset the latest measurement time + latest_measurement_time_ = objects_time; + RCLCPP_WARN( + node_.get_logger(), + "InputManager::updateTimingStatus %s: Resetting the latest measurement time to %f", + long_name_.c_str(), objects_time.seconds()); + } else { + // Update only if the object time is newer than the latest measurement time + latest_measurement_time_ = + latest_measurement_time_ < objects_time ? objects_time : latest_measurement_time_; + } + + // Update the initial count + if (initial_count_ < INITIALIZATION_COUNT) { + initial_count_++; + } +} + +void InputStream::getObjectsOlderThan( + const rclcpp::Time & object_latest_time, const rclcpp::Time & object_oldest_time, + ObjectsList & objects_list) +{ + if (object_latest_time < object_oldest_time) { + RCLCPP_WARN( + node_.get_logger(), + "InputManager::getObjectsOlderThan %s: Invalid object time interval, object_latest_time: %f, " + "object_oldest_time: %f", + long_name_.c_str(), object_latest_time.seconds(), object_oldest_time.seconds()); + return; + } + + for (const auto & object : objects_que_) { + const rclcpp::Time object_time = rclcpp::Time(object.header.stamp); + + // remove objects older than the specified duration + if (object_time < object_oldest_time) { + objects_que_.pop_front(); + continue; + } + + // Add the object if the object is older than the specified latest time + if (object_latest_time >= object_time) { + std::pair object_pair(index_, object); + objects_list.push_back(object_pair); + // remove the object from the queue + objects_que_.pop_front(); + } + } +} + +//////////////////////////// +/////// InputManager /////// +//////////////////////////// +InputManager::InputManager(rclcpp::Node & node) : node_(node) +{ + latest_exported_object_time_ = node_.now() - rclcpp::Duration::from_seconds(3.0); +} + +void InputManager::init(const std::vector & input_channels) +{ + // Check input sizes + input_size_ = input_channels.size(); + if (input_size_ == 0) { + RCLCPP_ERROR(node_.get_logger(), "InputManager::init No input streams"); + return; + } + + // Initialize input streams + sub_objects_array_.resize(input_size_); + bool is_any_spawn_enabled = false; + for (size_t i = 0; i < input_size_; i++) { + uint index(i); + InputStream input_stream(node_, index); + input_stream.init(input_channels[i]); + input_stream.setTriggerFunction( + std::bind(&InputManager::onTrigger, this, std::placeholders::_1)); + input_streams_.push_back(std::make_shared(input_stream)); + is_any_spawn_enabled |= input_streams_.at(i)->isSpawnEnabled(); + + // Set subscription + RCLCPP_INFO( + node_.get_logger(), "InputManager::init Initializing %s input stream from %s", + input_channels[i].long_name.c_str(), input_channels[i].input_topic.c_str()); + std::function func = + std::bind(&InputStream::onMessage, input_streams_.at(i), std::placeholders::_1); + sub_objects_array_.at(i) = node_.create_subscription( + input_channels[i].input_topic, rclcpp::QoS{1}, func); + } + + // Check if any spawn enabled input streams + if (!is_any_spawn_enabled) { + RCLCPP_ERROR(node_.get_logger(), "InputManager::init No spawn enabled input streams"); + return; + } + is_initialized_ = true; +} + +void InputManager::onTrigger(const uint & index) const +{ + // when the target stream triggers, call the trigger function + if (index == target_stream_idx_ && func_trigger_) { + func_trigger_(); + } +} + +void InputManager::getObjectTimeInterval( + const rclcpp::Time & now, rclcpp::Time & object_latest_time, + rclcpp::Time & object_oldest_time) const +{ + // Set the object time interval + + // 1. object_latest_time + // The object_latest_time is the current time minus the target stream latency + object_latest_time = + now - rclcpp::Duration::from_seconds(target_stream_latency_ - 0.1 * target_stream_latency_std_); + + // check the target stream can be included in the object time interval + if (input_streams_.at(target_stream_idx_)->isTimeInitialized()) { + const rclcpp::Time latest_measurement_time = + input_streams_.at(target_stream_idx_)->getLatestMeasurementTime(); + // if the object_latest_time is older than the latest measurement time, set it to the latest + // object time + object_latest_time = + object_latest_time < latest_measurement_time ? latest_measurement_time : object_latest_time; + } + + // 2. object_oldest_time + // The default object_oldest_time is to have a 1-second time interval + const rclcpp::Time object_oldest_time_default = + object_latest_time - rclcpp::Duration::from_seconds(1.0); + if (latest_exported_object_time_ < object_oldest_time_default) { + // if the latest exported object time is too old, set to the default + object_oldest_time = object_oldest_time_default; + } else if (latest_exported_object_time_ > object_latest_time) { + // if the latest exported object time is newer than the object_latest_time, set to the default + object_oldest_time = object_oldest_time_default; + } else { + // The object_oldest_time is the latest exported object time + object_oldest_time = latest_exported_object_time_; + } +} + +void InputManager::optimizeTimings() +{ + double max_latency_mean = 0.0; + uint selected_stream_idx = 0; + double selected_stream_latency_std = 0.1; + double selected_stream_interval = 0.1; + double selected_stream_interval_std = 0.01; + + { + // ANALYSIS: Get the streams statistics + // select the stream that has the maximum latency + double latency_mean, latency_var, interval_mean, interval_var; + for (const auto & input_stream : input_streams_) { + if (!input_stream->isTimeInitialized()) continue; + input_stream->getTimeStatistics(latency_mean, latency_var, interval_mean, interval_var); + if (latency_mean > max_latency_mean) { + max_latency_mean = latency_mean; + selected_stream_idx = input_stream->getIndex(); + selected_stream_latency_std = std::sqrt(latency_var); + selected_stream_interval = interval_mean; + selected_stream_interval_std = std::sqrt(interval_var); + } + } + } + + // Set the target stream index, which has the maximum latency + // trigger will be called next time + // if no stream is initialized, the target stream index will be 0 and wait for the initialization + target_stream_idx_ = selected_stream_idx; + target_stream_latency_ = max_latency_mean; + target_stream_latency_std_ = selected_stream_latency_std; + target_stream_interval_ = selected_stream_interval; + target_stream_interval_std_ = selected_stream_interval_std; +} + +bool InputManager::getObjects(const rclcpp::Time & now, ObjectsList & objects_list) +{ + if (!is_initialized_) { + RCLCPP_INFO(node_.get_logger(), "InputManager::getObjects Input manager is not initialized"); + return false; + } + + // Clear the objects + objects_list.clear(); + + // Get the time interval for the objects + rclcpp::Time object_latest_time; + rclcpp::Time object_oldest_time; + getObjectTimeInterval(now, object_latest_time, object_oldest_time); + + // Optimize the target stream, latency, and its band + // The result will be used for the next time, so the optimization is after getting the time + // interval + optimizeTimings(); + + // Get objects from all input streams + // adds up to the objects vector for efficient processing + for (const auto & input_stream : input_streams_) { + input_stream->getObjectsOlderThan(object_latest_time, object_oldest_time, objects_list); + } + + // Sort objects by timestamp + std::sort( + objects_list.begin(), objects_list.end(), + [](const std::pair & a, const std::pair & b) { + return (rclcpp::Time(a.second.header.stamp) - rclcpp::Time(b.second.header.stamp)).seconds() < + 0; + }); + + // Update the latest exported object time + bool is_any_object = !objects_list.empty(); + if (is_any_object) { + latest_exported_object_time_ = rclcpp::Time(objects_list.back().second.header.stamp); + } else { + // check time jump back + if (now < latest_exported_object_time_) { + RCLCPP_WARN( + node_.get_logger(), + "InputManager::getObjects Detected jump back in time, now: %f, " + "latest_exported_object_time_: %f", + now.seconds(), latest_exported_object_time_.seconds()); + // reset the latest exported object time to 3 seconds ago, + const rclcpp::Time latest_exported_object_time_default = + now - rclcpp::Duration::from_seconds(3.0); + latest_exported_object_time_ = latest_exported_object_time_default; + } else { + // No objects in the object list, no update for the latest exported object time + RCLCPP_DEBUG( + node_.get_logger(), + "InputManager::getObjects No objects in the object list, object time band from %f to %f", + (now - object_oldest_time).seconds(), (now - object_latest_time).seconds()); + } + } + + return is_any_object; +} + +} // namespace multi_object_tracker diff --git a/perception/multi_object_tracker/src/processor/processor.cpp b/perception/multi_object_tracker/src/processor/processor.cpp index 0d56e16b431e9..08df50fa66993 100644 --- a/perception/multi_object_tracker/src/processor/processor.cpp +++ b/perception/multi_object_tracker/src/processor/processor.cpp @@ -1,4 +1,4 @@ -// Copyright 2024 Tier IV, Inc. +// 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. @@ -11,8 +11,6 @@ // 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" @@ -25,8 +23,9 @@ using Label = autoware_auto_perception_msgs::msg::ObjectClassification; -TrackerProcessor::TrackerProcessor(const std::map & tracker_map) -: tracker_map_(tracker_map) +TrackerProcessor::TrackerProcessor( + const std::map & tracker_map, const size_t & channel_size) +: tracker_map_(tracker_map), channel_size_(channel_size) { // Set tracker lifetime parameters max_elapsed_time_ = 1.0; // [s] @@ -50,7 +49,7 @@ void TrackerProcessor::predict(const rclcpp::Time & 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) + const std::unordered_map & direct_assignment, const uint & channel_index) { int tracker_idx = 0; const auto & time = detected_objects.header.stamp; @@ -59,9 +58,10 @@ void TrackerProcessor::update( 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); + (*(tracker_itr)) + ->updateWithMeasurement(associated_object, time, self_transform, channel_index); } else { // not found - (*(tracker_itr))->updateWithoutMeasurement(); + (*(tracker_itr))->updateWithoutMeasurement(time); } } } @@ -69,7 +69,7 @@ void TrackerProcessor::update( 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 std::unordered_map & reverse_assignment, const uint & channel_index) { const auto & time = detected_objects.header.stamp; for (size_t i = 0; i < detected_objects.objects.size(); ++i) { @@ -77,34 +77,43 @@ void TrackerProcessor::spawn( continue; } const auto & new_object = detected_objects.objects.at(i); - std::shared_ptr tracker = createNewTracker(new_object, time, self_transform); + std::shared_ptr tracker = + createNewTracker(new_object, time, self_transform, channel_index); 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 geometry_msgs::msg::Transform & self_transform, const uint & channel_index) 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); + return std::make_shared( + time, object, self_transform, channel_size_, channel_index); if (tracker == "big_vehicle_tracker") - return std::make_shared(time, object, self_transform); + return std::make_shared( + time, object, self_transform, channel_size_, channel_index); if (tracker == "multi_vehicle_tracker") - return std::make_shared(time, object, self_transform); + return std::make_shared( + time, object, self_transform, channel_size_, channel_index); if (tracker == "normal_vehicle_tracker") - return std::make_shared(time, object, self_transform); + return std::make_shared( + time, object, self_transform, channel_size_, channel_index); if (tracker == "pass_through_tracker") - return std::make_shared(time, object, self_transform); + return std::make_shared( + time, object, self_transform, channel_size_, channel_index); if (tracker == "pedestrian_and_bicycle_tracker") - return std::make_shared(time, object, self_transform); + return std::make_shared( + time, object, self_transform, channel_size_, channel_index); if (tracker == "pedestrian_tracker") - return std::make_shared(time, object, self_transform); + return std::make_shared( + time, object, self_transform, channel_size_, channel_index); } - return std::make_shared(time, object, self_transform); + return std::make_shared( + time, object, self_transform, channel_size_, channel_index); } void TrackerProcessor::prune(const rclcpp::Time & time) diff --git a/perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp index 12c340516c6c1..fdc93419b326a 100644 --- a/perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp +++ b/perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp @@ -44,13 +44,17 @@ using Label = autoware_auto_perception_msgs::msg::ObjectClassification; BicycleTracker::BicycleTracker( const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & /*self_transform*/) -: Tracker(time, object.classification), + const geometry_msgs::msg::Transform & /*self_transform*/, const size_t channel_size, + const uint & channel_index) +: Tracker(time, object.classification, channel_size), logger_(rclcpp::get_logger("BicycleTracker")), z_(object.kinematics.pose_with_covariance.pose.position.z) { object_ = object; + // initialize existence probability + initializeExistenceProbabilities(channel_index, object.existence_probability); + // Initialize parameters // measurement noise covariance: detector uncertainty + ego vehicle motion uncertainty double r_stddev_x = 0.5; // in vehicle coordinate [m] @@ -67,10 +71,12 @@ BicycleTracker::BicycleTracker( } else { bounding_box_ = {1.0, 0.5, 1.7}; } - // set minimum size - bounding_box_.length = std::max(bounding_box_.length, 0.3); - bounding_box_.width = std::max(bounding_box_.width, 0.3); - bounding_box_.height = std::max(bounding_box_.height, 0.3); + // set maximum and minimum size + constexpr double max_size = 5.0; + constexpr double min_size = 0.3; + bounding_box_.length = std::min(std::max(bounding_box_.length, min_size), max_size); + bounding_box_.width = std::min(std::max(bounding_box_.width, min_size), max_size); + bounding_box_.height = std::min(std::max(bounding_box_.height, min_size), max_size); // Set motion model parameters { @@ -121,9 +127,9 @@ BicycleTracker::BicycleTracker( constexpr double p0_stddev_y = 0.5; // in object coordinate [m] constexpr double p0_stddev_yaw = tier4_autoware_utils::deg2rad(25); // in map coordinate [rad] - constexpr double p0_cov_x = std::pow(p0_stddev_x, 2.0); - constexpr double p0_cov_y = std::pow(p0_stddev_y, 2.0); - constexpr double p0_cov_yaw = std::pow(p0_stddev_yaw, 2.0); + constexpr double p0_cov_x = p0_stddev_x * p0_stddev_x; + constexpr double p0_cov_y = p0_stddev_y * p0_stddev_y; + constexpr double p0_cov_yaw = p0_stddev_yaw * p0_stddev_yaw; const double cos_yaw = std::cos(yaw); const double sin_yaw = std::sin(yaw); @@ -168,7 +174,9 @@ autoware_auto_perception_msgs::msg::DetectedObject BicycleTracker::getUpdatingOb // OBJECT SHAPE MODEL // convert to bounding box if input is convex shape if (object.shape.type != autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { - utils::convertConvexHullToBoundingBox(object, updating_object); + if (!utils::convertConvexHullToBoundingBox(object, updating_object)) { + updating_object = object; + } } else { updating_object = object; } @@ -222,22 +230,38 @@ bool BicycleTracker::measureWithPose( bool BicycleTracker::measureWithShape( const autoware_auto_perception_msgs::msg::DetectedObject & object) { + autoware_auto_perception_msgs::msg::DetectedObject bbox_object; if (!object.shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { // do not update shape if the input is not a bounding box - return true; + return false; } - constexpr double gain = 0.1; - constexpr double gain_inv = 1.0 - gain; + // check bound box size abnormality + constexpr double size_max = 30.0; // [m] + constexpr double size_min = 0.1; // [m] + if ( + bbox_object.shape.dimensions.x > size_max || bbox_object.shape.dimensions.y > size_max || + bbox_object.shape.dimensions.z > size_max) { + return false; + } else if ( + bbox_object.shape.dimensions.x < size_min || bbox_object.shape.dimensions.y < size_min || + bbox_object.shape.dimensions.z < size_min) { + return false; + } // update object size - bounding_box_.length = gain_inv * bounding_box_.length + gain * object.shape.dimensions.x; - bounding_box_.width = gain_inv * bounding_box_.width + gain * object.shape.dimensions.y; - bounding_box_.height = gain_inv * bounding_box_.height + gain * object.shape.dimensions.z; - // set minimum size - bounding_box_.length = std::max(bounding_box_.length, 0.3); - bounding_box_.width = std::max(bounding_box_.width, 0.3); - bounding_box_.height = std::max(bounding_box_.height, 0.3); + constexpr double gain = 0.1; + constexpr double gain_inv = 1.0 - gain; + bounding_box_.length = gain_inv * bounding_box_.length + gain * bbox_object.shape.dimensions.x; + bounding_box_.width = gain_inv * bounding_box_.width + gain * bbox_object.shape.dimensions.y; + bounding_box_.height = gain_inv * bounding_box_.height + gain * bbox_object.shape.dimensions.z; + + // set maximum and minimum size + constexpr double max_size = 5.0; + constexpr double min_size = 0.3; + bounding_box_.length = std::min(std::max(bounding_box_.length, min_size), max_size); + bounding_box_.width = std::min(std::max(bounding_box_.width, min_size), max_size); + bounding_box_.height = std::min(std::max(bounding_box_.height, min_size), max_size); // update motion model motion_model_.updateExtendedState(bounding_box_.length); diff --git a/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp index 3c73b9f19cfbb..5e3ba8d614e7e 100644 --- a/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp +++ b/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp @@ -44,14 +44,18 @@ using Label = autoware_auto_perception_msgs::msg::ObjectClassification; BigVehicleTracker::BigVehicleTracker( const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform) -: Tracker(time, object.classification), + const geometry_msgs::msg::Transform & self_transform, const size_t channel_size, + const uint & channel_index) +: Tracker(time, object.classification, channel_size), logger_(rclcpp::get_logger("BigVehicleTracker")), z_(object.kinematics.pose_with_covariance.pose.position.z), tracking_offset_(Eigen::Vector2d::Zero()) { object_ = object; + // initialize existence probability + initializeExistenceProbabilities(channel_index, object.existence_probability); + // Initialize parameters // measurement noise covariance: detector uncertainty + ego vehicle motion uncertainty float r_stddev_x = 0.5; // in vehicle coordinate [m] @@ -75,16 +79,24 @@ BigVehicleTracker::BigVehicleTracker( last_input_bounding_box_ = bounding_box_; } else { autoware_auto_perception_msgs::msg::DetectedObject bbox_object; - utils::convertConvexHullToBoundingBox(object, bbox_object); - bounding_box_ = { - bbox_object.shape.dimensions.x, bbox_object.shape.dimensions.y, - bbox_object.shape.dimensions.z}; + if (!utils::convertConvexHullToBoundingBox(object, bbox_object)) { + RCLCPP_WARN( + logger_, + "BigVehicleTracker::BigVehicleTracker: Failed to convert convex hull to bounding box."); + bounding_box_ = {6.0, 2.0, 2.0}; // default value + } else { + bounding_box_ = { + bbox_object.shape.dimensions.x, bbox_object.shape.dimensions.y, + bbox_object.shape.dimensions.z}; + } last_input_bounding_box_ = bounding_box_; } - // set minimum size - bounding_box_.length = std::max(bounding_box_.length, 0.3); - bounding_box_.width = std::max(bounding_box_.width, 0.3); - bounding_box_.height = std::max(bounding_box_.height, 0.3); + // set maximum and minimum size + constexpr double max_size = 30.0; + constexpr double min_size = 1.0; + bounding_box_.length = std::min(std::max(bounding_box_.length, min_size), max_size); + bounding_box_.width = std::min(std::max(bounding_box_.width, min_size), max_size); + bounding_box_.height = std::min(std::max(bounding_box_.height, min_size), max_size); // Set motion model parameters { @@ -135,9 +147,9 @@ BigVehicleTracker::BigVehicleTracker( constexpr double p0_stddev_y = 0.5; // in object coordinate [m] constexpr double p0_stddev_yaw = tier4_autoware_utils::deg2rad(25); // in map coordinate [rad] - constexpr double p0_cov_x = std::pow(p0_stddev_x, 2.0); - constexpr double p0_cov_y = std::pow(p0_stddev_y, 2.0); - constexpr double p0_cov_yaw = std::pow(p0_stddev_yaw, 2.0); + constexpr double p0_cov_x = p0_stddev_x * p0_stddev_x; + constexpr double p0_cov_y = p0_stddev_y * p0_stddev_y; + constexpr double p0_cov_yaw = p0_stddev_yaw * p0_stddev_yaw; const double cos_yaw = std::cos(yaw); const double sin_yaw = std::sin(yaw); @@ -191,7 +203,12 @@ autoware_auto_perception_msgs::msg::DetectedObject BigVehicleTracker::getUpdatin // convert to bounding box if input is convex shape autoware_auto_perception_msgs::msg::DetectedObject bbox_object; if (object.shape.type != autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { - utils::convertConvexHullToBoundingBox(object, bbox_object); + if (!utils::convertConvexHullToBoundingBox(object, bbox_object)) { + RCLCPP_WARN( + logger_, + "BigVehicleTracker::getUpdatingObject: Failed to convert convex hull to bounding box."); + bbox_object = object; + } } else { bbox_object = object; } @@ -302,6 +319,20 @@ bool BigVehicleTracker::measureWithPose( bool BigVehicleTracker::measureWithShape( const autoware_auto_perception_msgs::msg::DetectedObject & object) { + if (!object.shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { + // do not update shape if the input is not a bounding box + return false; + } + + // check object size abnormality + constexpr double size_max = 40.0; // [m] + constexpr double size_min = 1.0; // [m] + if (object.shape.dimensions.x > size_max || object.shape.dimensions.y > size_max) { + return false; + } else if (object.shape.dimensions.x < size_min || object.shape.dimensions.y < size_min) { + return false; + } + constexpr double gain = 0.1; constexpr double gain_inv = 1.0 - gain; @@ -311,10 +342,13 @@ bool BigVehicleTracker::measureWithShape( bounding_box_.height = gain_inv * bounding_box_.height + gain * object.shape.dimensions.z; last_input_bounding_box_ = { object.shape.dimensions.x, object.shape.dimensions.y, object.shape.dimensions.z}; - // set minimum size - bounding_box_.length = std::max(bounding_box_.length, 0.3); - bounding_box_.width = std::max(bounding_box_.width, 0.3); - bounding_box_.height = std::max(bounding_box_.height, 0.3); + + // set maximum and minimum size + constexpr double max_size = 30.0; + constexpr double min_size = 1.0; + bounding_box_.length = std::min(std::max(bounding_box_.length, min_size), max_size); + bounding_box_.width = std::min(std::max(bounding_box_.width, min_size), max_size); + bounding_box_.height = std::min(std::max(bounding_box_.height, min_size), max_size); // update motion model motion_model_.updateExtendedState(bounding_box_.length); diff --git a/perception/multi_object_tracker/src/tracker/model/multiple_vehicle_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/multiple_vehicle_tracker.cpp index 4f0fb4d7871f2..c925976f65e7e 100644 --- a/perception/multi_object_tracker/src/tracker/model/multiple_vehicle_tracker.cpp +++ b/perception/multi_object_tracker/src/tracker/model/multiple_vehicle_tracker.cpp @@ -22,11 +22,14 @@ using Label = autoware_auto_perception_msgs::msg::ObjectClassification; MultipleVehicleTracker::MultipleVehicleTracker( const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform) -: Tracker(time, object.classification), - normal_vehicle_tracker_(time, object, self_transform), - big_vehicle_tracker_(time, object, self_transform) + const geometry_msgs::msg::Transform & self_transform, const size_t channel_size, + const uint & channel_index) +: Tracker(time, object.classification, channel_size), + normal_vehicle_tracker_(time, object, self_transform, channel_size, channel_index), + big_vehicle_tracker_(time, object, self_transform, channel_size, channel_index) { + // initialize existence probability + initializeExistenceProbabilities(channel_index, object.existence_probability); } bool MultipleVehicleTracker::predict(const rclcpp::Time & time) diff --git a/perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp index 19fc5a2f71122..9907da2105825 100644 --- a/perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp +++ b/perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp @@ -44,14 +44,18 @@ using Label = autoware_auto_perception_msgs::msg::ObjectClassification; NormalVehicleTracker::NormalVehicleTracker( const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform) -: Tracker(time, object.classification), + const geometry_msgs::msg::Transform & self_transform, const size_t channel_size, + const uint & channel_index) +: Tracker(time, object.classification, channel_size), logger_(rclcpp::get_logger("NormalVehicleTracker")), z_(object.kinematics.pose_with_covariance.pose.position.z), tracking_offset_(Eigen::Vector2d::Zero()) { object_ = object; + // initialize existence probability + initializeExistenceProbabilities(channel_index, object.existence_probability); + // Initialize parameters // measurement noise covariance: detector uncertainty + ego vehicle motion uncertainty float r_stddev_x = 0.5; // in vehicle coordinate [m] @@ -75,16 +79,25 @@ NormalVehicleTracker::NormalVehicleTracker( last_input_bounding_box_ = bounding_box_; } else { autoware_auto_perception_msgs::msg::DetectedObject bbox_object; - utils::convertConvexHullToBoundingBox(object, bbox_object); - bounding_box_ = { - bbox_object.shape.dimensions.x, bbox_object.shape.dimensions.y, - bbox_object.shape.dimensions.z}; + if (!utils::convertConvexHullToBoundingBox(object, bbox_object)) { + RCLCPP_WARN( + logger_, + "NormalVehicleTracker::NormalVehicleTracker: Failed to convert convex hull to bounding " + "box."); + bounding_box_ = {3.0, 2.0, 1.8}; // default value + } else { + bounding_box_ = { + bbox_object.shape.dimensions.x, bbox_object.shape.dimensions.y, + bbox_object.shape.dimensions.z}; + } last_input_bounding_box_ = bounding_box_; } - // set minimum size - bounding_box_.length = std::max(bounding_box_.length, 0.3); - bounding_box_.width = std::max(bounding_box_.width, 0.3); - bounding_box_.height = std::max(bounding_box_.height, 0.3); + // set maximum and minimum size + constexpr double max_size = 20.0; + constexpr double min_size = 1.0; + bounding_box_.length = std::min(std::max(bounding_box_.length, min_size), max_size); + bounding_box_.width = std::min(std::max(bounding_box_.width, min_size), max_size); + bounding_box_.height = std::min(std::max(bounding_box_.height, min_size), max_size); // Set motion model parameters { @@ -135,9 +148,9 @@ NormalVehicleTracker::NormalVehicleTracker( constexpr double p0_stddev_y = 0.3; // in object coordinate [m] constexpr double p0_stddev_yaw = tier4_autoware_utils::deg2rad(25); // in map coordinate [rad] - constexpr double p0_cov_x = std::pow(p0_stddev_x, 2.0); - constexpr double p0_cov_y = std::pow(p0_stddev_y, 2.0); - constexpr double p0_cov_yaw = std::pow(p0_stddev_yaw, 2.0); + constexpr double p0_cov_x = p0_stddev_x * p0_stddev_x; + constexpr double p0_cov_y = p0_stddev_y * p0_stddev_y; + constexpr double p0_cov_yaw = p0_stddev_yaw * p0_stddev_yaw; const double cos_yaw = std::cos(yaw); const double sin_yaw = std::sin(yaw); @@ -191,7 +204,13 @@ autoware_auto_perception_msgs::msg::DetectedObject NormalVehicleTracker::getUpda // convert to bounding box if input is convex shape autoware_auto_perception_msgs::msg::DetectedObject bbox_object; if (object.shape.type != autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { - utils::convertConvexHullToBoundingBox(object, bbox_object); + if (!utils::convertConvexHullToBoundingBox(object, bbox_object)) { + RCLCPP_WARN( + logger_, + "NormalVehicleTracker::getUpdatingObject: Failed to convert convex hull to bounding box."); + bbox_object = object; + } + } else { bbox_object = object; } @@ -302,6 +321,20 @@ bool NormalVehicleTracker::measureWithPose( bool NormalVehicleTracker::measureWithShape( const autoware_auto_perception_msgs::msg::DetectedObject & object) { + if (!object.shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { + // do not update shape if the input is not a bounding box + return false; + } + + // check object size abnormality + constexpr double size_max = 30.0; // [m] + constexpr double size_min = 1.0; // [m] + if (object.shape.dimensions.x > size_max || object.shape.dimensions.y > size_max) { + return false; + } else if (object.shape.dimensions.x < size_min || object.shape.dimensions.y < size_min) { + return false; + } + constexpr double gain = 0.1; constexpr double gain_inv = 1.0 - gain; @@ -311,10 +344,13 @@ bool NormalVehicleTracker::measureWithShape( bounding_box_.height = gain_inv * bounding_box_.height + gain * object.shape.dimensions.z; last_input_bounding_box_ = { object.shape.dimensions.x, object.shape.dimensions.y, object.shape.dimensions.z}; - // set minimum size - bounding_box_.length = std::max(bounding_box_.length, 0.3); - bounding_box_.width = std::max(bounding_box_.width, 0.3); - bounding_box_.height = std::max(bounding_box_.height, 0.3); + + // set maximum and minimum size + constexpr double max_size = 20.0; + constexpr double min_size = 1.0; + bounding_box_.length = std::min(std::max(bounding_box_.length, min_size), max_size); + bounding_box_.width = std::min(std::max(bounding_box_.width, min_size), max_size); + bounding_box_.height = std::min(std::max(bounding_box_.height, min_size), max_size); // update motion model motion_model_.updateExtendedState(bounding_box_.length); diff --git a/perception/multi_object_tracker/src/tracker/model/pass_through_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/pass_through_tracker.cpp index 2084ac28e70f0..e1f4383cf11a3 100644 --- a/perception/multi_object_tracker/src/tracker/model/pass_through_tracker.cpp +++ b/perception/multi_object_tracker/src/tracker/model/pass_through_tracker.cpp @@ -37,13 +37,17 @@ PassThroughTracker::PassThroughTracker( const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & /*self_transform*/) -: Tracker(time, object.classification), + const geometry_msgs::msg::Transform & /*self_transform*/, const size_t channel_size, + const uint & channel_index) +: Tracker(time, object.classification, channel_size), logger_(rclcpp::get_logger("PassThroughTracker")), last_update_time_(time) { object_ = object; prev_observed_object_ = object; + + // initialize existence probability + initializeExistenceProbabilities(channel_index, object.existence_probability); } bool PassThroughTracker::predict(const rclcpp::Time & time) diff --git a/perception/multi_object_tracker/src/tracker/model/pedestrian_and_bicycle_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/pedestrian_and_bicycle_tracker.cpp index d61a9a02ccd80..e399dade880fa 100644 --- a/perception/multi_object_tracker/src/tracker/model/pedestrian_and_bicycle_tracker.cpp +++ b/perception/multi_object_tracker/src/tracker/model/pedestrian_and_bicycle_tracker.cpp @@ -22,11 +22,14 @@ using Label = autoware_auto_perception_msgs::msg::ObjectClassification; PedestrianAndBicycleTracker::PedestrianAndBicycleTracker( const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform) -: Tracker(time, object.classification), - pedestrian_tracker_(time, object, self_transform), - bicycle_tracker_(time, object, self_transform) + const geometry_msgs::msg::Transform & self_transform, const size_t channel_size, + const uint & channel_index) +: Tracker(time, object.classification, channel_size), + pedestrian_tracker_(time, object, self_transform, channel_size, channel_index), + bicycle_tracker_(time, object, self_transform, channel_size, channel_index) { + // initialize existence probability + initializeExistenceProbabilities(channel_index, object.existence_probability); } bool PedestrianAndBicycleTracker::predict(const rclcpp::Time & time) diff --git a/perception/multi_object_tracker/src/tracker/model/pedestrian_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/pedestrian_tracker.cpp index e1c07388836f6..6891bf6f63500 100644 --- a/perception/multi_object_tracker/src/tracker/model/pedestrian_tracker.cpp +++ b/perception/multi_object_tracker/src/tracker/model/pedestrian_tracker.cpp @@ -44,13 +44,17 @@ using Label = autoware_auto_perception_msgs::msg::ObjectClassification; PedestrianTracker::PedestrianTracker( const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & /*self_transform*/) -: Tracker(time, object.classification), + const geometry_msgs::msg::Transform & /*self_transform*/, const size_t channel_size, + const uint & channel_index) +: Tracker(time, object.classification, channel_size), logger_(rclcpp::get_logger("PedestrianTracker")), z_(object.kinematics.pose_with_covariance.pose.position.z) { object_ = object; + // initialize existence probability + initializeExistenceProbabilities(channel_index, object.existence_probability); + // Initialize parameters // measurement noise covariance float r_stddev_x = 0.4; // [m] @@ -62,19 +66,23 @@ PedestrianTracker::PedestrianTracker( // OBJECT SHAPE MODEL bounding_box_ = {0.5, 0.5, 1.7}; - cylinder_ = {0.3, 1.7}; + cylinder_ = {0.5, 1.7}; if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { bounding_box_ = { object.shape.dimensions.x, object.shape.dimensions.y, object.shape.dimensions.z}; } else if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::CYLINDER) { cylinder_ = {object.shape.dimensions.x, object.shape.dimensions.z}; + } else if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::POLYGON) { + // do not update polygon shape } - // set minimum size - bounding_box_.length = std::max(bounding_box_.length, 0.3); - bounding_box_.width = std::max(bounding_box_.width, 0.3); - bounding_box_.height = std::max(bounding_box_.height, 0.3); - cylinder_.width = std::max(cylinder_.width, 0.3); - cylinder_.height = std::max(cylinder_.height, 0.3); + // set maximum and minimum size + constexpr double max_size = 5.0; + constexpr double min_size = 0.3; + bounding_box_.length = std::min(std::max(bounding_box_.length, min_size), max_size); + bounding_box_.width = std::min(std::max(bounding_box_.width, min_size), max_size); + bounding_box_.height = std::min(std::max(bounding_box_.height, min_size), max_size); + cylinder_.width = std::min(std::max(cylinder_.width, min_size), max_size); + cylinder_.height = std::min(std::max(cylinder_.height, min_size), max_size); // Set motion model parameters { @@ -114,9 +122,9 @@ PedestrianTracker::PedestrianTracker( constexpr double p0_stddev_y = 2.0; // in object coordinate [m] constexpr double p0_stddev_yaw = tier4_autoware_utils::deg2rad(1000); // in map coordinate [rad] - constexpr double p0_cov_x = std::pow(p0_stddev_x, 2.0); - constexpr double p0_cov_y = std::pow(p0_stddev_y, 2.0); - constexpr double p0_cov_yaw = std::pow(p0_stddev_yaw, 2.0); + constexpr double p0_cov_x = p0_stddev_x * p0_stddev_x; + constexpr double p0_cov_y = p0_stddev_y * p0_stddev_y; + constexpr double p0_cov_yaw = p0_stddev_yaw * p0_stddev_yaw; const double cos_yaw = std::cos(yaw); const double sin_yaw = std::sin(yaw); @@ -205,22 +213,46 @@ bool PedestrianTracker::measureWithShape( constexpr double gain_inv = 1.0 - gain; if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { + // check bound box size abnormality + constexpr double size_max = 30.0; // [m] + constexpr double size_min = 0.1; // [m] + if ( + object.shape.dimensions.x > size_max || object.shape.dimensions.y > size_max || + object.shape.dimensions.z > size_max) { + return false; + } else if ( + object.shape.dimensions.x < size_min || object.shape.dimensions.y < size_min || + object.shape.dimensions.z < size_min) { + return false; + } + // update bounding box size bounding_box_.length = gain_inv * bounding_box_.length + gain * object.shape.dimensions.x; bounding_box_.width = gain_inv * bounding_box_.width + gain * object.shape.dimensions.y; bounding_box_.height = gain_inv * bounding_box_.height + gain * object.shape.dimensions.z; } else if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::CYLINDER) { + // check cylinder size abnormality + constexpr double size_max = 30.0; // [m] + constexpr double size_min = 0.1; // [m] + if (object.shape.dimensions.x > size_max || object.shape.dimensions.z > size_max) { + return false; + } else if (object.shape.dimensions.x < size_min || object.shape.dimensions.z < size_min) { + return false; + } cylinder_.width = gain_inv * cylinder_.width + gain * object.shape.dimensions.x; cylinder_.height = gain_inv * cylinder_.height + gain * object.shape.dimensions.z; } else { + // do not update polygon shape return false; } - // set minimum size - bounding_box_.length = std::max(bounding_box_.length, 0.3); - bounding_box_.width = std::max(bounding_box_.width, 0.3); - bounding_box_.height = std::max(bounding_box_.height, 0.3); - cylinder_.width = std::max(cylinder_.width, 0.3); - cylinder_.height = std::max(cylinder_.height, 0.3); + // set maximum and minimum size + constexpr double max_size = 5.0; + constexpr double min_size = 0.3; + bounding_box_.length = std::min(std::max(bounding_box_.length, min_size), max_size); + bounding_box_.width = std::min(std::max(bounding_box_.width, min_size), max_size); + bounding_box_.height = std::min(std::max(bounding_box_.height, min_size), max_size); + cylinder_.width = std::min(std::max(cylinder_.width, min_size), max_size); + cylinder_.height = std::min(std::max(cylinder_.height, min_size), max_size); return true; } diff --git a/perception/multi_object_tracker/src/tracker/model/tracker_base.cpp b/perception/multi_object_tracker/src/tracker/model/tracker_base.cpp index a3320ff54afcb..4318da0569721 100644 --- a/perception/multi_object_tracker/src/tracker/model/tracker_base.cpp +++ b/perception/multi_object_tracker/src/tracker/model/tracker_base.cpp @@ -21,9 +21,18 @@ #include #include +namespace +{ +float updateProbability(float prior, float true_positive, float false_positive) +{ + return (prior * true_positive) / (prior * true_positive + (1 - prior) * false_positive); +} +} // namespace + Tracker::Tracker( const rclcpp::Time & time, - const std::vector & classification) + const std::vector & classification, + const size_t & channel_size) : classification_(classification), no_measurement_count_(0), total_no_measurement_count_(0), @@ -34,23 +43,81 @@ Tracker::Tracker( std::mt19937 gen(std::random_device{}()); std::independent_bits_engine bit_eng(gen); std::generate(uuid_.uuid.begin(), uuid_.uuid.end(), bit_eng); + + // Initialize existence probabilities + existence_probabilities_.resize(channel_size, 0.0); +} + +void Tracker::initializeExistenceProbabilities( + const uint & channel_index, const float & existence_probability) +{ + // The initial existence probability is modeled + // since the incoming object's existence probability is not reliable + // existence probability on each channel + constexpr float initial_existence_probability = 0.1; + existence_probabilities_[channel_index] = initial_existence_probability; + + // total existence probability + total_existence_probability_ = existence_probability; } bool Tracker::updateWithMeasurement( const autoware_auto_perception_msgs::msg::DetectedObject & object, - const rclcpp::Time & measurement_time, const geometry_msgs::msg::Transform & self_transform) + const rclcpp::Time & measurement_time, const geometry_msgs::msg::Transform & self_transform, + const uint & channel_index) { - no_measurement_count_ = 0; - ++total_measurement_count_; + // Update existence probability + { + no_measurement_count_ = 0; + ++total_measurement_count_; + + // existence probability on each channel + const double delta_time = (measurement_time - last_update_with_measurement_time_).seconds(); + const double decay_rate = -log(0.5) / 0.3; // 50% decay in 0.3s + constexpr float probability_true_detection = 0.9; + constexpr float probability_false_detection = 0.2; + + // update measured channel probability + existence_probabilities_[channel_index] = updateProbability( + existence_probabilities_[channel_index], probability_true_detection, + probability_false_detection); + // decay other channel probabilities + for (size_t i = 0; i < existence_probabilities_.size(); ++i) { + if (i == channel_index) { + continue; + } + existence_probabilities_[i] *= std::exp(decay_rate * delta_time); + } + + // update total existence probability + const float & existence_probability_from_object = object.existence_probability; + total_existence_probability_ = updateProbability( + total_existence_probability_, existence_probability_from_object, probability_false_detection); + } + last_update_with_measurement_time_ = measurement_time; + + // Update object measure(object, measurement_time, self_transform); + return true; } -bool Tracker::updateWithoutMeasurement() +bool Tracker::updateWithoutMeasurement(const rclcpp::Time & now) { + // Update existence probability ++no_measurement_count_; ++total_no_measurement_count_; + { + // decay existence probability + double const delta_time = (now - last_update_with_measurement_time_).seconds(); + const double decay_rate = -log(0.5) / 0.3; // 50% decay in 0.3s + for (size_t i = 0; i < existence_probabilities_.size(); ++i) { + existence_probabilities_[i] *= std::exp(-decay_rate * delta_time); + } + total_existence_probability_ *= std::exp(-decay_rate * delta_time); + } + return true; } diff --git a/perception/multi_object_tracker/src/tracker/model/unknown_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/unknown_tracker.cpp index 450bb2d94abb6..04638267f7ad8 100644 --- a/perception/multi_object_tracker/src/tracker/model/unknown_tracker.cpp +++ b/perception/multi_object_tracker/src/tracker/model/unknown_tracker.cpp @@ -38,13 +38,17 @@ UnknownTracker::UnknownTracker( const rclcpp::Time & time, const autoware_auto_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & /*self_transform*/) -: Tracker(time, object.classification), + const geometry_msgs::msg::Transform & /*self_transform*/, const size_t channel_size, + const uint & channel_index) +: Tracker(time, object.classification, channel_size), logger_(rclcpp::get_logger("UnknownTracker")), z_(object.kinematics.pose_with_covariance.pose.position.z) { object_ = object; + // initialize existence probability + initializeExistenceProbabilities(channel_index, object.existence_probability); + // initialize params // measurement noise covariance constexpr double r_stddev_x = 1.0; // [m] 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/occupancy_grid_map_outlier_filter/include/occupancy_grid_map_outlier_filter/occupancy_grid_map_outlier_filter_nodelet.hpp b/perception/occupancy_grid_map_outlier_filter/include/occupancy_grid_map_outlier_filter/occupancy_grid_map_outlier_filter_nodelet.hpp index 1d7d01bfbab55..0faa40255a1ca 100644 --- a/perception/occupancy_grid_map_outlier_filter/include/occupancy_grid_map_outlier_filter/occupancy_grid_map_outlier_filter_nodelet.hpp +++ b/perception/occupancy_grid_map_outlier_filter/include/occupancy_grid_map_outlier_filter/occupancy_grid_map_outlier_filter_nodelet.hpp @@ -46,18 +46,16 @@ using geometry_msgs::msg::Pose; using nav_msgs::msg::OccupancyGrid; using sensor_msgs::msg::PointCloud2; using std_msgs::msg::Header; -using PclPointCloud = pcl::PointCloud; class RadiusSearch2dFilter { public: explicit RadiusSearch2dFilter(rclcpp::Node & node); void filter( - const PclPointCloud & input, const Pose & pose, PclPointCloud & output, - PclPointCloud & outlier); + const PointCloud2 & input, const Pose & pose, PointCloud2 & output, PointCloud2 & outlier); void filter( - const PclPointCloud & high_conf_input, const PclPointCloud & low_conf_input, const Pose & pose, - PclPointCloud & output, PclPointCloud & outlier); + const PointCloud2 & high_conf_input, const PointCloud2 & low_conf_input, const Pose & pose, + PointCloud2 & output, PointCloud2 & outlier); private: float search_radius_; @@ -79,22 +77,25 @@ class OccupancyGridMapOutlierFilterComponent : public rclcpp::Node const PointCloud2::ConstSharedPtr & input_pointcloud); void filterByOccupancyGridMap( const OccupancyGrid & occupancy_grid_map, const PointCloud2 & pointcloud, - PclPointCloud & high_confidence, PclPointCloud & low_confidence, PclPointCloud & out_ogm); + PointCloud2 & high_confidence, PointCloud2 & low_confidence, PointCloud2 & out_ogm); void splitPointCloudFrontBack( const PointCloud2::ConstSharedPtr & input_pc, PointCloud2 & front_pc, PointCloud2 & behind_pc); + void initializerPointCloud2(const PointCloud2 & input, PointCloud2 & output); + void finalizePointCloud2(const PointCloud2 & input, PointCloud2 & output); + void concatPointCloud2(PointCloud2 & output, const PointCloud2 & input); private: class Debugger { public: explicit Debugger(OccupancyGridMapOutlierFilterComponent & node); - void publishOutlier(const PclPointCloud & input, const Header & header); - void publishHighConfidence(const PclPointCloud & input, const Header & header); - void publishLowConfidence(const PclPointCloud & input, const Header & header); + void publishOutlier(const PointCloud2 & input, const Header & header); + void publishHighConfidence(const PointCloud2 & input, const Header & header); + void publishLowConfidence(const PointCloud2 & input, const Header & header); private: void transformToBaseLink( - const PclPointCloud & input, const Header & header, PointCloud2 & output); + const PointCloud2 & input, const Header & header, PointCloud2 & output); rclcpp::Publisher::SharedPtr outlier_pointcloud_pub_; rclcpp::Publisher::SharedPtr low_confidence_pointcloud_pub_; rclcpp::Publisher::SharedPtr high_confidence_pointcloud_pub_; diff --git a/perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp b/perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp index 65eb336269fe4..bbd138030d76f 100644 --- a/perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp +++ b/perception/occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_nodelet.cpp @@ -116,19 +116,23 @@ RadiusSearch2dFilter::RadiusSearch2dFilter(rclcpp::Node & node) } void RadiusSearch2dFilter::filter( - const PclPointCloud & input, const Pose & pose, PclPointCloud & output, PclPointCloud & outlier) + const PointCloud2 & input, const Pose & pose, PointCloud2 & output, PointCloud2 & outlier) { - const auto & xyz_cloud = input; pcl::PointCloud::Ptr xy_cloud(new pcl::PointCloud); - xy_cloud->points.resize(xyz_cloud.points.size()); - for (size_t i = 0; i < xyz_cloud.points.size(); ++i) { - xy_cloud->points[i].x = xyz_cloud.points[i].x; - xy_cloud->points[i].y = xyz_cloud.points[i].y; + int point_step = input.point_step; + int x_offset = input.fields[pcl::getFieldIndex(input, "x")].offset; + int y_offset = input.fields[pcl::getFieldIndex(input, "y")].offset; + xy_cloud->points.resize(input.data.size() / point_step); + for (size_t i = 0; i < input.data.size() / point_step; ++i) { + std::memcpy(&xy_cloud->points[i].x, &input.data[i * point_step + x_offset], sizeof(float)); + std::memcpy(&xy_cloud->points[i].y, &input.data[i * point_step + y_offset], sizeof(float)); } std::vector k_indices(xy_cloud->points.size()); std::vector k_distances(xy_cloud->points.size()); kd_tree_->setInputCloud(xy_cloud); + size_t output_size = 0; + size_t outlier_size = 0; for (size_t i = 0; i < xy_cloud->points.size(); ++i) { const float distance = std::hypot(xy_cloud->points[i].x - pose.position.x, xy_cloud->points[i].y - pose.position.y); @@ -139,42 +143,57 @@ void RadiusSearch2dFilter::filter( kd_tree_->radiusSearch(i, search_radius_, k_indices, k_distances, min_points_threshold); if (min_points_threshold <= points_num) { - output.points.push_back(xyz_cloud.points.at(i)); + std::memcpy(&output.data[output_size], &input.data[i * point_step], point_step); + output_size += point_step; } else { - outlier.points.push_back(xyz_cloud.points.at(i)); + std::memcpy(&outlier.data[outlier_size], &input.data[i * point_step], point_step); + outlier_size += point_step; } } + output.data.resize(output_size); + outlier.data.resize(outlier_size); } void RadiusSearch2dFilter::filter( - const PclPointCloud & high_conf_input, const PclPointCloud & low_conf_input, const Pose & pose, - PclPointCloud & output, PclPointCloud & outlier) + const PointCloud2 & high_conf_xyz_cloud, const PointCloud2 & low_conf_xyz_cloud, + const Pose & pose, PointCloud2 & output, PointCloud2 & outlier) { - const auto & high_conf_xyz_cloud = high_conf_input; - const auto & low_conf_xyz_cloud = low_conf_input; // check the limit points number - if (low_conf_xyz_cloud.points.size() > max_filter_points_nb_) { + if (low_conf_xyz_cloud.width > max_filter_points_nb_) { RCLCPP_WARN( rclcpp::get_logger("OccupancyGridMapOutlierFilterComponent"), "Skip outlier filter since too much low_confidence pointcloud!"); return; } - + int x_offset = low_conf_xyz_cloud.fields[pcl::getFieldIndex(low_conf_xyz_cloud, "x")].offset; + int y_offset = low_conf_xyz_cloud.fields[pcl::getFieldIndex(low_conf_xyz_cloud, "y")].offset; + int point_step = low_conf_xyz_cloud.point_step; pcl::PointCloud::Ptr xy_cloud(new pcl::PointCloud); - xy_cloud->points.resize(low_conf_xyz_cloud.points.size() + high_conf_xyz_cloud.points.size()); - for (size_t i = 0; i < low_conf_xyz_cloud.points.size(); ++i) { - xy_cloud->points[i].x = low_conf_xyz_cloud.points[i].x; - xy_cloud->points[i].y = low_conf_xyz_cloud.points[i].y; + xy_cloud->points.resize(low_conf_xyz_cloud.width + high_conf_xyz_cloud.width); + for (size_t i = 0; i < low_conf_xyz_cloud.width; ++i) { + std::memcpy( + &xy_cloud->points[i].x, &low_conf_xyz_cloud.data[i * point_step + x_offset], sizeof(float)); + std::memcpy( + &xy_cloud->points[i].y, &low_conf_xyz_cloud.data[i * point_step + y_offset], sizeof(float)); } - for (size_t i = low_conf_xyz_cloud.points.size(); i < xy_cloud->points.size(); ++i) { - xy_cloud->points[i].x = high_conf_xyz_cloud.points[i - low_conf_xyz_cloud.points.size()].x; - xy_cloud->points[i].y = high_conf_xyz_cloud.points[i - low_conf_xyz_cloud.points.size()].y; + + for (size_t i = low_conf_xyz_cloud.width; i < xy_cloud->points.size(); ++i) { + size_t high_conf_xyz_cloud_index = i - low_conf_xyz_cloud.width; + std::memcpy( + &xy_cloud->points[i].x, + &high_conf_xyz_cloud.data[high_conf_xyz_cloud_index * point_step + x_offset], sizeof(float)); + std::memcpy( + &xy_cloud->points[i].y, + &high_conf_xyz_cloud.data[high_conf_xyz_cloud_index * point_step + y_offset], sizeof(float)); } std::vector k_indices(xy_cloud->points.size()); std::vector k_distances(xy_cloud->points.size()); kd_tree_->setInputCloud(xy_cloud); - for (size_t i = 0; i < low_conf_xyz_cloud.points.size(); ++i) { + + size_t output_size = 0; + size_t outlier_size = 0; + for (size_t i = 0; i < low_conf_xyz_cloud.data.size() / low_conf_xyz_cloud.point_step; ++i) { const float distance = std::hypot(xy_cloud->points[i].x - pose.position.x, xy_cloud->points[i].y - pose.position.y); const int min_points_threshold = std::min( @@ -184,11 +203,20 @@ void RadiusSearch2dFilter::filter( kd_tree_->radiusSearch(i, search_radius_, k_indices, k_distances, min_points_threshold); if (min_points_threshold <= points_num) { - output.points.push_back(low_conf_xyz_cloud.points.at(i)); + std::memcpy( + &output.data[output_size], &low_conf_xyz_cloud.data[i * low_conf_xyz_cloud.point_step], + low_conf_xyz_cloud.point_step); + output_size += low_conf_xyz_cloud.point_step; } else { - outlier.points.push_back(low_conf_xyz_cloud.points.at(i)); + std::memcpy( + &outlier.data[outlier_size], &low_conf_xyz_cloud.data[i * low_conf_xyz_cloud.point_step], + low_conf_xyz_cloud.point_step); + outlier_size += low_conf_xyz_cloud.point_step; } } + + output.data.resize(output_size); + outlier.data.resize(outlier_size); } OccupancyGridMapOutlierFilterComponent::OccupancyGridMapOutlierFilterComponent( @@ -234,61 +262,52 @@ OccupancyGridMapOutlierFilterComponent::OccupancyGridMapOutlierFilterComponent( if (enable_debugger) { debugger_ptr_ = std::make_shared(*this); } - published_time_publisher_ = std::make_unique(this); } void OccupancyGridMapOutlierFilterComponent::splitPointCloudFrontBack( const PointCloud2::ConstSharedPtr & input_pc, PointCloud2 & front_pc, PointCloud2 & behind_pc) { + int x_offset = input_pc->fields[pcl::getFieldIndex(*input_pc, "x")].offset; + int point_step = input_pc->point_step; size_t front_count = 0; size_t behind_count = 0; - for (sensor_msgs::PointCloud2ConstIterator x(*input_pc, "x"); x != x.end(); ++x) { - if (*x < 0.0) { + for (size_t global_offset = 0; global_offset < input_pc->data.size(); + global_offset += point_step) { + float x; + std::memcpy(&x, &input_pc->data[global_offset + x_offset], sizeof(float)); + if (x < 0.0) { + std::memcpy( + &behind_pc.data[behind_count * point_step], &input_pc->data[global_offset], + input_pc->point_step); behind_count++; } else { + std::memcpy( + &front_pc.data[front_count * point_step], &input_pc->data[global_offset], + input_pc->point_step); front_count++; } } - - sensor_msgs::PointCloud2Modifier front_pc_modifier(front_pc); - sensor_msgs::PointCloud2Modifier behind_pc_modifier(behind_pc); - front_pc_modifier.setPointCloud2FieldsByString(1, "xyz"); - behind_pc_modifier.setPointCloud2FieldsByString(1, "xyz"); - front_pc_modifier.resize(front_count); - behind_pc_modifier.resize(behind_count); - - sensor_msgs::PointCloud2Iterator fr_iter(front_pc, "x"); - sensor_msgs::PointCloud2Iterator be_iter(behind_pc, "x"); - - for (sensor_msgs::PointCloud2ConstIterator in_iter(*input_pc, "x"); - in_iter != in_iter.end(); ++in_iter) { - if (*in_iter < 0.0) { - *be_iter = in_iter[0]; - be_iter[1] = in_iter[1]; - be_iter[2] = in_iter[2]; - ++be_iter; - } else { - *fr_iter = in_iter[0]; - fr_iter[1] = in_iter[1]; - fr_iter[2] = in_iter[2]; - ++fr_iter; - } - } - - front_pc.header = input_pc->header; - behind_pc.header = input_pc->header; + front_pc.data.resize(front_count * point_step); + behind_pc.data.resize(behind_count * point_step); } void OccupancyGridMapOutlierFilterComponent::onOccupancyGridMapAndPointCloud2( const OccupancyGrid::ConstSharedPtr & input_ogm, const PointCloud2::ConstSharedPtr & input_pc) { stop_watch_ptr_->toc("processing_time", true); // Transform to occupancy grid map frame - PointCloud2 ogm_frame_pc{}; - PointCloud2 input_front_pc{}; + PointCloud2 input_behind_pc{}; - PointCloud2 ogm_frame_input_behind_pc{}; + PointCloud2 input_front_pc{}; + initializerPointCloud2(*input_pc, input_front_pc); + initializerPointCloud2(*input_pc, input_behind_pc); + // Split pointcloud into front and behind of the vehicle to reduce the calculation cost splitPointCloudFrontBack(input_pc, input_front_pc, input_behind_pc); + finalizePointCloud2(*input_pc, input_front_pc); + finalizePointCloud2(*input_pc, input_behind_pc); + + PointCloud2 ogm_frame_pc{}; + PointCloud2 ogm_frame_input_behind_pc{}; if ( !transformPointcloud(input_front_pc, *tf2_, input_ogm->header.frame_id, ogm_frame_pc) || !transformPointcloud( @@ -296,16 +315,22 @@ void OccupancyGridMapOutlierFilterComponent::onOccupancyGridMapAndPointCloud2( return; } // Occupancy grid map based filter - PclPointCloud high_confidence_pc{}; - PclPointCloud low_confidence_pc{}; - PclPointCloud out_ogm_pc{}; - PclPointCloud ogm_frame_behind_pc; - pcl::fromROSMsg(ogm_frame_input_behind_pc, ogm_frame_behind_pc); + PointCloud2 high_confidence_pc{}; + PointCloud2 low_confidence_pc{}; + PointCloud2 out_ogm_pc{}; + initializerPointCloud2(ogm_frame_pc, high_confidence_pc); + initializerPointCloud2(ogm_frame_pc, low_confidence_pc); + initializerPointCloud2(ogm_frame_pc, out_ogm_pc); + // split front pointcloud into high and low confidence and out of map pointcloud filterByOccupancyGridMap( *input_ogm, ogm_frame_pc, high_confidence_pc, low_confidence_pc, out_ogm_pc); // Apply Radius search 2d filter for low confidence pointcloud - PclPointCloud filtered_low_confidence_pc{}; - PclPointCloud outlier_pc{}; + PointCloud2 filtered_low_confidence_pc{}; + PointCloud2 outlier_pc{}; + initializerPointCloud2(low_confidence_pc, outlier_pc); + initializerPointCloud2(low_confidence_pc, filtered_low_confidence_pc); + initializerPointCloud2(low_confidence_pc, outlier_pc); + if (radius_search_2d_filter_ptr_) { auto pc_frame_pose_stamped = getPoseStamped( *tf2_, input_ogm->header.frame_id, input_pc->header.frame_id, input_ogm->header.stamp); @@ -313,26 +338,29 @@ void OccupancyGridMapOutlierFilterComponent::onOccupancyGridMapAndPointCloud2( high_confidence_pc, low_confidence_pc, pc_frame_pose_stamped.pose, filtered_low_confidence_pc, outlier_pc); } else { - outlier_pc = low_confidence_pc; + std::memcpy(&outlier_pc.data[0], &low_confidence_pc.data[0], low_confidence_pc.data.size()); + outlier_pc.data.resize(low_confidence_pc.data.size()); } // Concatenate high confidence pointcloud from occupancy grid map and non-outlier pointcloud - PclPointCloud concat_pc = - high_confidence_pc + filtered_low_confidence_pc + out_ogm_pc + ogm_frame_behind_pc; - // Convert to ros msg + PointCloud2 ogm_frame_filtered_pc{}; + concatPointCloud2(ogm_frame_filtered_pc, high_confidence_pc); + concatPointCloud2(ogm_frame_filtered_pc, filtered_low_confidence_pc); + concatPointCloud2(ogm_frame_filtered_pc, out_ogm_pc); + concatPointCloud2(ogm_frame_filtered_pc, ogm_frame_input_behind_pc); + finalizePointCloud2(ogm_frame_pc, ogm_frame_filtered_pc); { - PointCloud2 ogm_frame_filtered_pc{}; auto base_link_frame_filtered_pc_ptr = std::make_unique(); - pcl::toROSMsg(concat_pc, ogm_frame_filtered_pc); ogm_frame_filtered_pc.header = ogm_frame_pc.header; if (!transformPointcloud( ogm_frame_filtered_pc, *tf2_, base_link_frame_, *base_link_frame_filtered_pc_ptr)) { return; } pointcloud_pub_->publish(std::move(base_link_frame_filtered_pc_ptr)); - published_time_publisher_->publish_if_subscribed( - pointcloud_pub_, ogm_frame_filtered_pc.header.stamp); } if (debugger_ptr_) { + finalizePointCloud2(ogm_frame_pc, high_confidence_pc); + finalizePointCloud2(ogm_frame_pc, filtered_low_confidence_pc); + finalizePointCloud2(ogm_frame_pc, outlier_pc); debugger_ptr_->publishHighConfidence(high_confidence_pc, ogm_frame_pc.header); debugger_ptr_->publishLowConfidence(filtered_low_confidence_pc, ogm_frame_pc.header); debugger_ptr_->publishOutlier(outlier_pc, ogm_frame_pc.header); @@ -349,24 +377,75 @@ void OccupancyGridMapOutlierFilterComponent::onOccupancyGridMapAndPointCloud2( } } +void OccupancyGridMapOutlierFilterComponent::initializerPointCloud2( + const PointCloud2 & input, PointCloud2 & output) +{ + output.point_step = input.point_step; + output.data.resize(input.data.size()); +} + +void OccupancyGridMapOutlierFilterComponent::finalizePointCloud2( + const PointCloud2 & input, PointCloud2 & output) +{ + output.header = input.header; + output.point_step = input.point_step; + output.fields = input.fields; + output.height = input.height; + output.is_bigendian = input.is_bigendian; + output.is_dense = input.is_dense; + output.width = output.data.size() / output.point_step / output.height; + output.row_step = output.data.size() / output.height; +} + +void OccupancyGridMapOutlierFilterComponent::concatPointCloud2( + PointCloud2 & output, const PointCloud2 & input) +{ + size_t output_size = output.data.size(); + output.data.resize(output.data.size() + input.data.size()); + std::memcpy(&output.data[output_size], &input.data[0], input.data.size()); +} void OccupancyGridMapOutlierFilterComponent::filterByOccupancyGridMap( const OccupancyGrid & occupancy_grid_map, const PointCloud2 & pointcloud, - PclPointCloud & high_confidence, PclPointCloud & low_confidence, PclPointCloud & out_ogm) + PointCloud2 & high_confidence, PointCloud2 & low_confidence, PointCloud2 & out_ogm) { - for (sensor_msgs::PointCloud2ConstIterator x(pointcloud, "x"), y(pointcloud, "y"), - z(pointcloud, "z"); - x != x.end(); ++x, ++y, ++z) { - const auto cost = getCost(occupancy_grid_map, *x, *y); + int x_offset = pointcloud.fields[pcl::getFieldIndex(pointcloud, "x")].offset; + int y_offset = pointcloud.fields[pcl::getFieldIndex(pointcloud, "y")].offset; + size_t high_confidence_size = 0; + size_t low_confidence_size = 0; + size_t out_ogm_size = 0; + + for (size_t global_offset = 0; global_offset < pointcloud.data.size(); + global_offset += pointcloud.point_step) { + float x; + float y; + std::memcpy(&x, &pointcloud.data[global_offset + x_offset], sizeof(float)); + std::memcpy(&y, &pointcloud.data[global_offset + y_offset], sizeof(float)); + + const auto cost = getCost(occupancy_grid_map, x, y); if (cost) { if (cost_threshold_ < *cost) { - high_confidence.push_back(pcl::PointXYZ(*x, *y, *z)); + std::memcpy( + &high_confidence.data[high_confidence_size], &pointcloud.data[global_offset], + pointcloud.point_step); + high_confidence_size += pointcloud.point_step; } else { - low_confidence.push_back(pcl::PointXYZ(*x, *y, *z)); + std::memcpy( + &low_confidence.data[low_confidence_size], &pointcloud.data[global_offset], + pointcloud.point_step); + low_confidence_size += pointcloud.point_step; } } else { - out_ogm.push_back(pcl::PointXYZ(*x, *y, *z)); + std::memcpy( + &out_ogm.data[out_ogm_size], &pointcloud.data[global_offset], pointcloud.point_step); + out_ogm_size += pointcloud.point_step; } } + high_confidence.data.resize(high_confidence_size); + low_confidence.data.resize(low_confidence_size); + out_ogm.data.resize(out_ogm_size); + finalizePointCloud2(pointcloud, high_confidence); + finalizePointCloud2(pointcloud, low_confidence); + finalizePointCloud2(pointcloud, out_ogm); } OccupancyGridMapOutlierFilterComponent::Debugger::Debugger( @@ -382,14 +461,14 @@ OccupancyGridMapOutlierFilterComponent::Debugger::Debugger( } void OccupancyGridMapOutlierFilterComponent::Debugger::publishOutlier( - const PclPointCloud & input, const Header & header) + const PointCloud2 & input, const Header & header) { auto output_ptr = std::make_unique(); transformToBaseLink(input, header, *output_ptr); outlier_pointcloud_pub_->publish(std::move(output_ptr)); } void OccupancyGridMapOutlierFilterComponent::Debugger::publishHighConfidence( - const PclPointCloud & input, const Header & header) + const PointCloud2 & input, const Header & header) { auto output_ptr = std::make_unique(); transformToBaseLink(input, header, *output_ptr); @@ -397,7 +476,7 @@ void OccupancyGridMapOutlierFilterComponent::Debugger::publishHighConfidence( } void OccupancyGridMapOutlierFilterComponent::Debugger::publishLowConfidence( - const PclPointCloud & input, const Header & header) + const PointCloud2 & input, const Header & header) { auto output_ptr = std::make_unique(); transformToBaseLink(input, header, *output_ptr); @@ -405,11 +484,8 @@ void OccupancyGridMapOutlierFilterComponent::Debugger::publishLowConfidence( } void OccupancyGridMapOutlierFilterComponent::Debugger::transformToBaseLink( - const PclPointCloud & pcl_input, const Header & header, PointCloud2 & output) + const PointCloud2 & ros_input, [[maybe_unused]] const Header & header, PointCloud2 & output) { - PointCloud2 ros_input{}; - pcl::toROSMsg(pcl_input, ros_input); - ros_input.header = header; transformPointcloud(ros_input, *(node_.tf2_), node_.base_link_frame_, output); } diff --git a/perception/probabilistic_occupancy_grid_map/README.md b/perception/probabilistic_occupancy_grid_map/README.md index 084c55d80d629..97d66bf9f648c 100644 --- a/perception/probabilistic_occupancy_grid_map/README.md +++ b/perception/probabilistic_occupancy_grid_map/README.md @@ -72,6 +72,26 @@ Additional argument is shown below: | `input_obstacle_pointcloud` | `false` | only for laserscan based method. If true, the node subscribe obstacle pointcloud | | `input_obstacle_and_raw_pointcloud` | `true` | only for laserscan based method. If true, the node subscribe both obstacle and raw pointcloud | +### Downsample input pointcloud(Optional) + +If you set `downsample_input_pointcloud` to `true`, the input pointcloud will be downsampled and following topics are also used. This feature is currently only for the pointcloud based occupancy grid map. + +- pointcloud_based_occupancy_grid_map method + +```yaml +# downsampled raw and obstacle pointcloud +/perception/occupancy_grid_map/obstacle/downsample/pointcloud +/perception/occupancy_grid_map/raw/downsample/pointcloud +``` + +- multi_lidar_pointcloud_based_point_cloud + +```yaml +# downsampled raw and obstacle pointcloud +/perception/occupancy_grid_map/obstacle/downsample/pointcloud +/perception/occupancy_grid_map//raw/downsample/pointcloud +``` + ### Test This package provides unit tests using `gtest`. diff --git a/perception/probabilistic_occupancy_grid_map/config/multi_lidar_pointcloud_based_occupancy_grid_map.param.yaml b/perception/probabilistic_occupancy_grid_map/config/multi_lidar_pointcloud_based_occupancy_grid_map.param.yaml index f9a1c4f930001..878bea4cd8ced 100644 --- a/perception/probabilistic_occupancy_grid_map/config/multi_lidar_pointcloud_based_occupancy_grid_map.param.yaml +++ b/perception/probabilistic_occupancy_grid_map/config/multi_lidar_pointcloud_based_occupancy_grid_map.param.yaml @@ -12,6 +12,10 @@ map_length_x: 150.0 # [m] map_length_y: 150.0 # [m] + # downsample input pointcloud + downsample_input_pointcloud: true + downsample_voxel_size: 0.25 # [m] + # each grid map parameters ogm_creation_config: height_filter: @@ -20,7 +24,7 @@ max_height: 2.0 enable_single_frame_mode: true # use sensor pointcloud to filter obstacle pointcloud - filter_obstacle_pointcloud_by_raw_pointcloud: true + filter_obstacle_pointcloud_by_raw_pointcloud: false grid_map_type: "OccupancyGridMapFixedBlindSpot" OccupancyGridMapFixedBlindSpot: diff --git a/perception/probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml b/perception/probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml index 8077bdec5008e..922d4be6d519f 100644 --- a/perception/probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml +++ b/perception/probabilistic_occupancy_grid_map/config/pointcloud_based_occupancy_grid_map.param.yaml @@ -8,6 +8,10 @@ min_height: -1.0 max_height: 2.0 + # downsample input pointcloud + downsample_input_pointcloud: true + downsample_voxel_size: 0.25 # [m] + enable_single_frame_mode: false # use sensor pointcloud to filter obstacle pointcloud filter_obstacle_pointcloud_by_raw_pointcloud: false diff --git a/perception/probabilistic_occupancy_grid_map/launch/multi_lidar_pointcloud_based_occupancy_grid_map.launch.py b/perception/probabilistic_occupancy_grid_map/launch/multi_lidar_pointcloud_based_occupancy_grid_map.launch.py index dccddfbe54196..b112dd0a84b83 100644 --- a/perception/probabilistic_occupancy_grid_map/launch/multi_lidar_pointcloud_based_occupancy_grid_map.launch.py +++ b/perception/probabilistic_occupancy_grid_map/launch/multi_lidar_pointcloud_based_occupancy_grid_map.launch.py @@ -92,6 +92,57 @@ def get_ogm_creation_config(total_config: dict, list_iter: int) -> dict: return ogm_creation_config +# generate downsample node +def get_downsample_filter_node(setting: dict) -> ComposableNode: + plugin_str = setting["plugin"] + voxel_size = setting["voxel_size"] + node_name = setting["node_name"] + return ComposableNode( + package="pointcloud_preprocessor", + plugin=plugin_str, + name=node_name, + remappings=[ + ("input", setting["input_topic"]), + ("output", setting["output_topic"]), + ], + parameters=[ + { + "voxel_size_x": voxel_size, + "voxel_size_y": voxel_size, + "voxel_size_z": voxel_size, + } + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + + +def get_downsample_preprocess_nodes(voxel_size: float, raw_pointcloud_topics: list) -> list: + nodes = [] + for i in range(len(raw_pointcloud_topics)): + raw_pointcloud_topic: str = raw_pointcloud_topics[i] + frame_name: str = raw_pointcloud_topic.split("/")[ + -2 + ] # `/sensing/lidar/top/pointcloud` -> `top + processed_pointcloud_topic: str = frame_name + "/raw/downsample/pointcloud" + raw_settings = { + "plugin": "pointcloud_preprocessor::PickupBasedVoxelGridDownsampleFilterComponent", + "node_name": "raw_pc_downsample_filter_" + frame_name, + "input_topic": raw_pointcloud_topic, + "output_topic": processed_pointcloud_topic, + "voxel_size": voxel_size, + } + nodes.append(get_downsample_filter_node(raw_settings)) + obstacle_settings = { + "plugin": "pointcloud_preprocessor::PickupBasedVoxelGridDownsampleFilterComponent", + "node_name": "obstacle_pc_downsample_filter", + "input_topic": LaunchConfiguration("input/obstacle_pointcloud"), + "output_topic": "/perception/occupancy_grid_map/obstacle/downsample/pointcloud", + "voxel_size": voxel_size, + } + nodes.append(get_downsample_filter_node(obstacle_settings)) + return nodes + + def launch_setup(context, *args, **kwargs): """Launch fusion based occupancy grid map creation nodes. @@ -118,20 +169,39 @@ def launch_setup(context, *args, **kwargs): LaunchConfiguration("pointcloud_container_name").perform(context), ) + # Down sample settings + downsample_input_pointcloud: bool = total_config["downsample_input_pointcloud"] + downsample_voxel_size: float = total_config["downsample_voxel_size"] + + # get obstacle pointcloud + obstacle_pointcloud_topic: str = ( + "/perception/occupancy_grid_map/obstacle/downsample/pointcloud" + if downsample_input_pointcloud + else LaunchConfiguration("input/obstacle_pointcloud").perform(context) + ) + for i in range(number_of_nodes): # load parameter file ogm_creation_config = get_ogm_creation_config(total_config, i) ogm_creation_config["updater_type"] = LaunchConfiguration("updater_type").perform(context) ogm_creation_config.update(updater_config) + raw_pointcloud_topic: str = fusion_config["raw_pointcloud_topics"][i] + frame_name: str = raw_pointcloud_topic.split("/")[ + -2 + ] # assume `/sensing/lidar/top/pointcloud` -> `top + if downsample_input_pointcloud: + raw_pointcloud_topic = "raw/downsample/pointcloud" + # generate composable node node = ComposableNode( package="probabilistic_occupancy_grid_map", plugin="occupancy_grid_map::PointcloudBasedOccupancyGridMapNode", - name="occupancy_grid_map_node_in_" + str(i), + name="occupancy_grid_map_node", + namespace=frame_name, remappings=[ - ("~/input/obstacle_pointcloud", LaunchConfiguration("input/obstacle_pointcloud")), - ("~/input/raw_pointcloud", fusion_config["raw_pointcloud_topics"][i]), + ("~/input/obstacle_pointcloud", obstacle_pointcloud_topic), + ("~/input/raw_pointcloud", raw_pointcloud_topic), ("~/output/occupancy_grid_map", fusion_config["fusion_input_ogm_topics"][i]), ], parameters=[ogm_creation_config], @@ -139,6 +209,12 @@ def launch_setup(context, *args, **kwargs): ) gridmap_generation_composable_nodes.append(node) + if downsample_input_pointcloud: + downsample_nodes = get_downsample_preprocess_nodes( + downsample_voxel_size, fusion_config["raw_pointcloud_topics"] + ) + gridmap_generation_composable_nodes.extend(downsample_nodes) + # 2. launch occupancy grid map fusion node gridmap_fusion_node = [ ComposableNode( diff --git a/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py b/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py index 29435c4ea8e24..c58e747f84af2 100644 --- a/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py +++ b/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py @@ -26,6 +26,47 @@ import yaml +def get_downsample_filter_node(setting: dict) -> ComposableNode: + plugin_str = setting["plugin"] + voxel_size = setting["voxel_size"] + node_name = setting["node_name"] + return ComposableNode( + package="pointcloud_preprocessor", + plugin=plugin_str, + name=node_name, + remappings=[ + ("input", setting["input_topic"]), + ("output", setting["output_topic"]), + ], + parameters=[ + { + "voxel_size_x": voxel_size, + "voxel_size_y": voxel_size, + "voxel_size_z": voxel_size, + } + ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], + ) + + +def get_downsample_preprocess_nodes(voxel_size: float) -> list: + raw_settings = { + "plugin": "pointcloud_preprocessor::PickupBasedVoxelGridDownsampleFilterComponent", + "node_name": "raw_pc_downsample_filter", + "input_topic": LaunchConfiguration("input/raw_pointcloud"), + "output_topic": "raw/downsample/pointcloud", + "voxel_size": voxel_size, + } + obstacle_settings = { + "plugin": "pointcloud_preprocessor::PickupBasedVoxelGridDownsampleFilterComponent", + "node_name": "obstacle_pc_downsample_filter", + "input_topic": LaunchConfiguration("input/obstacle_pointcloud"), + "output_topic": "obstacle/downsample/pointcloud", + "voxel_size": voxel_size, + } + return [get_downsample_filter_node(raw_settings), get_downsample_filter_node(obstacle_settings)] + + def launch_setup(context, *args, **kwargs): # load parameter files param_file = LaunchConfiguration("param_file").perform(context) @@ -38,7 +79,21 @@ def launch_setup(context, *args, **kwargs): with open(updater_param_file, "r") as f: occupancy_grid_map_updater_params = yaml.safe_load(f)["/**"]["ros__parameters"] - composable_nodes = [ + # composable nodes + composable_nodes = [] + + # add downsample process + downsample_input_pointcloud: bool = pointcloud_based_occupancy_grid_map_node_params[ + "downsample_input_pointcloud" + ] + if downsample_input_pointcloud: + voxel_grid_size: float = pointcloud_based_occupancy_grid_map_node_params[ + "downsample_voxel_size" + ] + downsample_preprocess_nodes = get_downsample_preprocess_nodes(voxel_grid_size) + composable_nodes.extend(downsample_preprocess_nodes) + + composable_nodes.append( ComposableNode( package="probabilistic_occupancy_grid_map", plugin="occupancy_grid_map::PointcloudBasedOccupancyGridMapNode", @@ -46,11 +101,15 @@ def launch_setup(context, *args, **kwargs): remappings=[ ( "~/input/obstacle_pointcloud", - LaunchConfiguration("input/obstacle_pointcloud"), + LaunchConfiguration("input/obstacle_pointcloud") + if not downsample_input_pointcloud + else "obstacle/downsample/pointcloud", ), ( "~/input/raw_pointcloud", - LaunchConfiguration("input/raw_pointcloud"), + LaunchConfiguration("input/raw_pointcloud") + if not downsample_input_pointcloud + else "raw/downsample/pointcloud", ), ("~/output/occupancy_grid_map", LaunchConfiguration("output")), ], @@ -60,8 +119,8 @@ def launch_setup(context, *args, **kwargs): {"updater_type": LaunchConfiguration("updater_type")}, ], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], - ), - ] + ) + ) occupancy_grid_map_container = ComposableNodeContainer( name=LaunchConfiguration("individual_container_name"), diff --git a/perception/probabilistic_occupancy_grid_map/package.xml b/perception/probabilistic_occupancy_grid_map/package.xml index a90ae78b03597..3efed07535504 100644 --- a/perception/probabilistic_occupancy_grid_map/package.xml +++ b/perception/probabilistic_occupancy_grid_map/package.xml @@ -34,6 +34,7 @@ tier4_autoware_utils visualization_msgs + pointcloud_preprocessor pointcloud_to_laserscan ament_cmake_gtest @@ -44,6 +45,7 @@ launch_testing launch_testing_ament_cmake launch_testing_ros + pointcloud_preprocessor ament_cmake diff --git a/perception/probabilistic_occupancy_grid_map/pointcloud-based-occupancy-grid-map.md b/perception/probabilistic_occupancy_grid_map/pointcloud-based-occupancy-grid-map.md index 7d2efb3468f3a..d8d69ed7866b6 100644 --- a/perception/probabilistic_occupancy_grid_map/pointcloud-based-occupancy-grid-map.md +++ b/perception/probabilistic_occupancy_grid_map/pointcloud-based-occupancy-grid-map.md @@ -77,18 +77,34 @@ $$ | ----------------------------- | ------------------------- | ------------------ | | `~/output/occupancy_grid_map` | `nav_msgs::OccupancyGrid` | occupancy grid map | +### Related topics + +If you set `downsample_input_pointcloud` to `true`, the input pointcloud will be downsampled and following topics are also used. + +- pointcloud_based_occupancy_grid_map method + +```yaml +# downsampled raw and obstacle pointcloud +/perception/occupancy_grid_map/obstacle/downsample/pointcloud +/perception/occupancy_grid_map/raw/downsample/pointcloud +``` + ## Parameters ### Node Parameters -| Name | Type | Description | -| ------------------- | ------ | -------------------------------------------------------------------------------------------------------------------------------- | -| `map_frame` | string | map frame | -| `base_link_frame` | string | base_link frame | -| `use_height_filter` | bool | whether to height filter for `~/input/obstacle_pointcloud` and `~/input/raw_pointcloud`? By default, the height is set to -1~2m. | -| `map_length` | double | The length of the map. -100 if it is 50~50[m] | -| `map_resolution` | double | The map cell resolution [m] | -| `grid_map_type` | string | The type of grid map for estimating `UNKNOWN` region behind obstacle point clouds | +| Name | Type | Description | +| ----------------------------- | ------ | -------------------------------------------------------------------------------------------------------------------------------- | +| `map_frame` | string | map frame | +| `base_link_frame` | string | base_link frame | +| `use_height_filter` | bool | whether to height filter for `~/input/obstacle_pointcloud` and `~/input/raw_pointcloud`? By default, the height is set to -1~2m. | +| `map_length` | double | The length of the map. -100 if it is 50~50[m] | +| `map_resolution` | double | The map cell resolution [m] | +| `grid_map_type` | string | The type of grid map for estimating `UNKNOWN` region behind obstacle point clouds | +| `scan_origin` | string | The origin of the scan. It should be a sensor frame. | +| `pub_debug_grid` | bool | Whether to publish debug grid maps | +| `downsample_input_pointcloud` | bool | Whether to downsample the input pointclouds. The downsampled pointclouds are used for the ray tracing. | +| `downsample_voxel_size` | double | The voxel size for the downsampled pointclouds. | ## Assumptions / Known limits diff --git a/perception/radar_object_tracker/CMakeLists.txt b/perception/radar_object_tracker/CMakeLists.txt index 7c1b98c10d14b..ade45847f8a9f 100644 --- a/perception/radar_object_tracker/CMakeLists.txt +++ b/perception/radar_object_tracker/CMakeLists.txt @@ -13,18 +13,23 @@ find_package(eigen3_cmake_module REQUIRED) find_package(Eigen3 REQUIRED) find_package(nlohmann_json REQUIRED) # for debug find_package(glog REQUIRED) +find_package(ament_cmake_gtest REQUIRED) include_directories( SYSTEM ${EIGEN3_INCLUDE_DIR} ) +ament_auto_add_library(radar_object_tracker_utils SHARED + src/utils/utils.cpp + src/utils/radar_object_tracker_utils.cpp +) + ament_auto_add_library(radar_object_tracker_node SHARED src/radar_object_tracker_node/radar_object_tracker_node.cpp src/tracker/model/tracker_base.cpp src/tracker/model/linear_motion_tracker.cpp src/tracker/model/constant_turn_rate_motion_tracker.cpp - src/utils/utils.cpp src/data_association/data_association.cpp src/data_association/mu_successive_shortest_path/mu_successive_shortest_path_wrapper.cpp ) @@ -34,6 +39,7 @@ target_link_libraries(radar_object_tracker_node yaml-cpp nlohmann_json::nlohmann_json # for debug glog::glog + radar_object_tracker_utils ) rclcpp_components_register_node(radar_object_tracker_node @@ -42,7 +48,21 @@ rclcpp_components_register_node(radar_object_tracker_node ) # testing -# todo +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + + ament_add_gtest(test_radar_object_tracker_utils + test/test_radar_object_tracker_utils.cpp + src/utils/radar_object_tracker_utils.cpp + ) + target_include_directories(test_radar_object_tracker_utils PRIVATE + ${CMAKE_CURRENT_SOURCE_DIR}/include + ) + target_link_libraries(test_radar_object_tracker_utils + radar_object_tracker_utils + ) +endif() # Package ament_auto_package( diff --git a/perception/radar_object_tracker/include/radar_object_tracker/utils/radar_object_tracker_utils.hpp b/perception/radar_object_tracker/include/radar_object_tracker/utils/radar_object_tracker_utils.hpp new file mode 100644 index 0000000000000..48f40f62e3963 --- /dev/null +++ b/perception/radar_object_tracker/include/radar_object_tracker/utils/radar_object_tracker_utils.hpp @@ -0,0 +1,77 @@ +// 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 RADAR_OBJECT_TRACKER__UTILS__RADAR_OBJECT_TRACKER_UTILS_HPP_ +#define RADAR_OBJECT_TRACKER__UTILS__RADAR_OBJECT_TRACKER_UTILS_HPP_ + +#include +#include + +#include + +#include + +#include +#include +#include +#include +#include + +#ifdef ROS_DISTRO_GALACTIC +#include +#else +#include +#endif + +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include +#include +namespace radar_object_tracker_utils +{ + +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); + +bool isDuplicated( + const std::pair & target_lanelet, + const lanelet::ConstLanelets & lanelets); + +bool checkCloseLaneletCondition( + const std::pair & lanelet, + const autoware_auto_perception_msgs::msg::TrackedObject & object, + const double max_distance_from_lane, const double max_angle_diff_from_lane); + +lanelet::ConstLanelets getClosestValidLanelets( + const autoware_auto_perception_msgs::msg::TrackedObject & object, + const lanelet::LaneletMapPtr & lanelet_map_ptr, const double max_distance_from_lane, + const double max_angle_diff_from_lane); + +bool hasValidVelocityDirectionToLanelet( + const autoware_auto_perception_msgs::msg::TrackedObject & object, + const lanelet::ConstLanelets & lanelets, const double max_lateral_velocity); + +} // namespace radar_object_tracker_utils + +#endif // RADAR_OBJECT_TRACKER__UTILS__RADAR_OBJECT_TRACKER_UTILS_HPP_ diff --git a/perception/radar_object_tracker/package.xml b/perception/radar_object_tracker/package.xml index a371d9054966a..5be2ccef1e6cc 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 @@ -33,6 +33,7 @@ ament_lint_auto autoware_lint_common + gtest ament_cmake 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..dc87a180451d8 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 @@ -14,6 +14,7 @@ #include "radar_object_tracker/radar_object_tracker_node/radar_object_tracker_node.hpp" +#include "radar_object_tracker/utils/radar_object_tracker_utils.hpp" #include "radar_object_tracker/utils/utils.hpp" #include @@ -36,158 +37,6 @@ #include #define EIGEN_MPL2_ONLY -namespace -{ -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 - 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; - } - - geometry_msgs::msg::TransformStamped self_transform_stamped; - self_transform_stamped = tf_buffer.lookupTransform( - /*target*/ target_frame_id, /*src*/ source_frame_id, time, - rclcpp::Duration::from_seconds(0.5)); - return self_transform_stamped.transform; - } catch (tf2::TransformException & ex) { - RCLCPP_WARN_STREAM(rclcpp::get_logger("radar_object_tracker"), ex.what()); - return boost::none; - } -} - -// check if lanelet is close enough to the target lanelet -bool isDuplicated( - const std::pair & target_lanelet, - const lanelet::ConstLanelets & lanelets) -{ - const double CLOSE_LANELET_THRESHOLD = 0.1; - for (const auto & lanelet : lanelets) { - const auto target_lanelet_end_p = target_lanelet.second.centerline2d().back(); - const auto lanelet_end_p = lanelet.centerline2d().back(); - const double dist = std::hypot( - target_lanelet_end_p.x() - lanelet_end_p.x(), target_lanelet_end_p.y() - lanelet_end_p.y()); - if (dist < CLOSE_LANELET_THRESHOLD) { - return true; - } - } - - return false; -} - -// check if the lanelet is valid for object tracking -bool checkCloseLaneletCondition( - const std::pair & lanelet, const TrackedObject & object, - const double max_distance_from_lane, const double max_angle_diff_from_lane) -{ - // Step1. If we only have one point in the centerline, we will ignore the lanelet - if (lanelet.second.centerline().size() <= 1) { - return false; - } - - // Step2. Check if the obstacle is inside or close enough to the lanelet - lanelet::BasicPoint2d search_point( - object.kinematics.pose_with_covariance.pose.position.x, - object.kinematics.pose_with_covariance.pose.position.y); - if (!lanelet::geometry::inside(lanelet.second, search_point)) { - const auto distance = lanelet.first; - if (distance > max_distance_from_lane) { - return false; - } - } - - // Step3. Calculate the angle difference between the lane angle and obstacle angle - const double object_yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); - const double lane_yaw = lanelet::utils::getLaneletAngle( - lanelet.second, object.kinematics.pose_with_covariance.pose.position); - const double delta_yaw = object_yaw - lane_yaw; - const double normalized_delta_yaw = tier4_autoware_utils::normalizeRadian(delta_yaw); - const double abs_norm_delta = std::fabs(normalized_delta_yaw); - - // Step4. Check if the closest lanelet is valid, and add all - // of the lanelets that are below max_dist and max_delta_yaw - const double object_vel = object.kinematics.twist_with_covariance.twist.linear.x; - const bool is_yaw_reversed = M_PI - max_angle_diff_from_lane < abs_norm_delta && object_vel < 0.0; - if (is_yaw_reversed || abs_norm_delta < max_angle_diff_from_lane) { - return true; - } - - return false; -} - -lanelet::ConstLanelets getClosestValidLanelets( - const TrackedObject & object, const lanelet::LaneletMapPtr & lanelet_map_ptr, - const double max_distance_from_lane, const double max_angle_diff_from_lane) -{ - // obstacle point - lanelet::BasicPoint2d search_point( - object.kinematics.pose_with_covariance.pose.position.x, - object.kinematics.pose_with_covariance.pose.position.y); - - // nearest lanelet - std::vector> surrounding_lanelets = - lanelet::geometry::findNearest(lanelet_map_ptr->laneletLayer, search_point, 10); - - // No Closest Lanelets - if (surrounding_lanelets.empty()) { - return {}; - } - - lanelet::ConstLanelets closest_lanelets; - for (const auto & lanelet : surrounding_lanelets) { - // Check if the close lanelets meet the necessary condition for start lanelets and - // Check if similar lanelet is inside the closest lanelet - if ( - !checkCloseLaneletCondition( - lanelet, object, max_distance_from_lane, max_angle_diff_from_lane) || - isDuplicated(lanelet, closest_lanelets)) { - continue; - } - - closest_lanelets.push_back(lanelet.second); - } - - return closest_lanelets; -} - -bool hasValidVelocityDirectionToLanelet( - const TrackedObject & object, const lanelet::ConstLanelets & lanelets, - const double max_lateral_velocity) -{ - // get object velocity direction - const double object_yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); - const double object_vel_x = object.kinematics.twist_with_covariance.twist.linear.x; - const double object_vel_y = object.kinematics.twist_with_covariance.twist.linear.y; - const double object_vel_yaw = std::atan2(object_vel_y, object_vel_x); // local frame - const double object_vel_yaw_global = - tier4_autoware_utils::normalizeRadian(object_yaw + object_vel_yaw); - const double object_vel = std::hypot(object_vel_x, object_vel_y); - - for (const auto & lanelet : lanelets) { - // get lanelet angle - const double lane_yaw = lanelet::utils::getLaneletAngle( - lanelet, object.kinematics.pose_with_covariance.pose.position); - const double delta_yaw = object_vel_yaw_global - lane_yaw; - const double normalized_delta_yaw = tier4_autoware_utils::normalizeRadian(delta_yaw); - - // get lateral velocity - const double lane_vel = object_vel * std::sin(normalized_delta_yaw); - // std::cout << "lane_vel: " << lane_vel << " , delta yaw:" << normalized_delta_yaw << " , - // object_vel " << object_vel <( @@ -289,7 +140,7 @@ void RadarObjectTrackerNode::onMap(const HADMapBin::ConstSharedPtr msg) void RadarObjectTrackerNode::onMeasurement( const autoware_auto_perception_msgs::msg::DetectedObjects::ConstSharedPtr input_objects_msg) { - const auto self_transform = getTransformAnonymous( + const auto self_transform = radar_object_tracker_utils::getTransformAnonymous( tf_buffer_, "base_link", world_frame_id_, input_objects_msg->header.stamp); if (!self_transform) { return; @@ -385,8 +236,8 @@ std::shared_ptr RadarObjectTrackerNode::createNewTracker( void RadarObjectTrackerNode::onTimer() { rclcpp::Time current_time = this->now(); - const auto self_transform = - getTransformAnonymous(tf_buffer_, world_frame_id_, "base_link", current_time); + const auto self_transform = radar_object_tracker_utils::getTransformAnonymous( + tf_buffer_, world_frame_id_, "base_link", current_time); if (!self_transform) { return; } @@ -432,14 +283,15 @@ void RadarObjectTrackerNode::mapBasedNoiseFilter( for (auto itr = list_tracker.begin(); itr != list_tracker.end(); ++itr) { autoware_auto_perception_msgs::msg::TrackedObject object; (*itr)->getTrackedObject(time, object); - const auto closest_lanelets = getClosestValidLanelets( + const auto closest_lanelets = radar_object_tracker_utils::getClosestValidLanelets( object, lanelet_map_ptr_, max_distance_from_lane_, max_angle_diff_from_lane_); // 1. If the object is not close to any lanelet, delete the tracker const bool no_closest_lanelet = closest_lanelets.empty(); // 2. If the object velocity direction is not close to the lanelet direction, delete the tracker const bool is_velocity_direction_close_to_lanelet = - hasValidVelocityDirectionToLanelet(object, closest_lanelets, max_lateral_velocity_); + radar_object_tracker_utils::hasValidVelocityDirectionToLanelet( + object, closest_lanelets, max_lateral_velocity_); if (no_closest_lanelet || !is_velocity_direction_close_to_lanelet) { // std::cout << "object removed due to map based noise filter" << " no close lanelet: " << // no_closest_lanelet << " velocity direction flag:" << is_velocity_direction_close_to_lanelet diff --git a/perception/radar_object_tracker/src/utils/radar_object_tracker_utils.cpp b/perception/radar_object_tracker/src/utils/radar_object_tracker_utils.cpp new file mode 100644 index 0000000000000..870e77cc20d41 --- /dev/null +++ b/perception/radar_object_tracker/src/utils/radar_object_tracker_utils.cpp @@ -0,0 +1,154 @@ +// 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 "radar_object_tracker/utils/radar_object_tracker_utils.hpp" + +namespace radar_object_tracker_utils +{ + +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 { + std::string errstr; + if (!tf_buffer.canTransform( + target_frame_id, source_frame_id, tf2::TimePointZero, tf2::Duration::zero(), &errstr)) { + return boost::none; + } + + geometry_msgs::msg::TransformStamped self_transform_stamped; + self_transform_stamped = tf_buffer.lookupTransform( + target_frame_id, source_frame_id, time, rclcpp::Duration::from_seconds(0.5)); + return self_transform_stamped.transform; + } catch (tf2::TransformException & ex) { + RCLCPP_WARN_STREAM(rclcpp::get_logger("radar_object_tracker"), ex.what()); + return boost::none; + } +} + +bool isDuplicated( + const std::pair & target_lanelet, + const lanelet::ConstLanelets & lanelets) +{ + const double CLOSE_LANELET_THRESHOLD = 0.1; + for (const auto & lanelet : lanelets) { + const auto target_lanelet_end_p = target_lanelet.second.centerline2d().back(); + const auto lanelet_end_p = lanelet.centerline2d().back(); + const double dist = std::hypot( + target_lanelet_end_p.x() - lanelet_end_p.x(), target_lanelet_end_p.y() - lanelet_end_p.y()); + if (dist < CLOSE_LANELET_THRESHOLD) { + return true; + } + } + + return false; +} + +bool checkCloseLaneletCondition( + const std::pair & lanelet, + const autoware_auto_perception_msgs::msg::TrackedObject & object, + const double max_distance_from_lane, const double max_angle_diff_from_lane) +{ + if (lanelet.second.centerline().size() <= 1) { + return false; + } + + lanelet::BasicPoint2d search_point( + object.kinematics.pose_with_covariance.pose.position.x, + object.kinematics.pose_with_covariance.pose.position.y); + if (!lanelet::geometry::inside(lanelet.second, search_point)) { + const auto distance = lanelet.first; + if (distance > max_distance_from_lane) { + return false; + } + } + + const double object_yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); + const double lane_yaw = lanelet::utils::getLaneletAngle( + lanelet.second, object.kinematics.pose_with_covariance.pose.position); + double object_motion_yaw = object_yaw; + bool velocity_is_reverted = object.kinematics.twist_with_covariance.twist.linear.x < 0.0; + if (velocity_is_reverted) { + object_motion_yaw = tier4_autoware_utils::normalizeRadian(object_yaw + M_PI); + } + const double delta_yaw = object_motion_yaw - lane_yaw; + const double normalized_delta_yaw = tier4_autoware_utils::normalizeRadian(delta_yaw); + const double abs_norm_delta_yaw = std::fabs(normalized_delta_yaw); + + if (abs_norm_delta_yaw > max_angle_diff_from_lane) { + return false; + } + + return true; +} + +lanelet::ConstLanelets getClosestValidLanelets( + const autoware_auto_perception_msgs::msg::TrackedObject & object, + const lanelet::LaneletMapPtr & lanelet_map_ptr, const double max_distance_from_lane, + const double max_angle_diff_from_lane) +{ + lanelet::BasicPoint2d search_point( + object.kinematics.pose_with_covariance.pose.position.x, + object.kinematics.pose_with_covariance.pose.position.y); + + std::vector> surrounding_lanelets = + lanelet::geometry::findNearest(lanelet_map_ptr->laneletLayer, search_point, 10); + + if (surrounding_lanelets.empty()) { + return {}; + } + + lanelet::ConstLanelets closest_lanelets; + for (const auto & lanelet : surrounding_lanelets) { + if ( + !checkCloseLaneletCondition( + lanelet, object, max_distance_from_lane, max_angle_diff_from_lane) || + isDuplicated(lanelet, closest_lanelets)) { + continue; + } + + closest_lanelets.push_back(lanelet.second); + } + + return closest_lanelets; +} + +bool hasValidVelocityDirectionToLanelet( + const autoware_auto_perception_msgs::msg::TrackedObject & object, + const lanelet::ConstLanelets & lanelets, const double max_lateral_velocity) +{ + const double object_yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); + const double object_vel_x = object.kinematics.twist_with_covariance.twist.linear.x; + const double object_vel_y = object.kinematics.twist_with_covariance.twist.linear.y; + const double object_vel_yaw = std::atan2(object_vel_y, object_vel_x); + const double object_vel_yaw_global = + tier4_autoware_utils::normalizeRadian(object_yaw + object_vel_yaw); + const double object_vel = std::hypot(object_vel_x, object_vel_y); + + for (const auto & lanelet : lanelets) { + const double lane_yaw = lanelet::utils::getLaneletAngle( + lanelet, object.kinematics.pose_with_covariance.pose.position); + const double delta_yaw = object_vel_yaw_global - lane_yaw; + const double normalized_delta_yaw = tier4_autoware_utils::normalizeRadian(delta_yaw); + + const double lane_vel = object_vel * std::sin(normalized_delta_yaw); + if (std::fabs(lane_vel) < max_lateral_velocity) { + return true; + } + } + return false; +} + +} // namespace radar_object_tracker_utils diff --git a/perception/radar_object_tracker/test/test_radar_object_tracker_utils.cpp b/perception/radar_object_tracker/test/test_radar_object_tracker_utils.cpp new file mode 100644 index 0000000000000..50b1de7132f6f --- /dev/null +++ b/perception/radar_object_tracker/test/test_radar_object_tracker_utils.cpp @@ -0,0 +1,121 @@ +// 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 "radar_object_tracker/utils/radar_object_tracker_utils.hpp" + +#include + +using autoware_auto_perception_msgs::msg::TrackedObject; +using radar_object_tracker_utils::checkCloseLaneletCondition; + +// helper function to create a dummy straight lanelet +lanelet::Lanelet createDummyStraightLanelet(double length, double width) +{ + lanelet::LineString3d left_line( + lanelet::utils::getId(), {lanelet::Point3d(lanelet::utils::getId(), 0, 0, 0), + lanelet::Point3d(lanelet::utils::getId(), length, 0, 0)}); + lanelet::LineString3d right_line( + lanelet::utils::getId(), {lanelet::Point3d(lanelet::utils::getId(), 0, width, 0), + lanelet::Point3d(lanelet::utils::getId(), length, width, 0)}); + lanelet::LineString3d center_line( + lanelet::utils::getId(), {lanelet::Point3d(lanelet::utils::getId(), 0, width / 2, 0), + lanelet::Point3d(lanelet::utils::getId(), length, width / 2, 0)}); + + // Correct constructor call + return lanelet::Lanelet( + lanelet::utils::getId(), left_line, right_line, lanelet::AttributeMap(), + lanelet::RegulatoryElementPtrs()); +} + +// helper function to create a dummy tracked object +TrackedObject createDummyTrackedObject(double x, double y, double yaw, double velocity) +{ + TrackedObject obj; + obj.kinematics.pose_with_covariance.pose.position.x = x; + obj.kinematics.pose_with_covariance.pose.position.y = y; + tf2::Quaternion q; + q.setRPY(0, 0, yaw); + obj.kinematics.pose_with_covariance.pose.orientation = tf2::toMsg(q); + obj.kinematics.twist_with_covariance.twist.linear.x = velocity; + return obj; +} + +// 1. Test checkCloseLaneletCondition +// 1. Inside lanelet +TEST(CheckCloseLaneletConditionTest, InsideLanelet) +{ + auto lanelet = createDummyStraightLanelet(100.0, 3.0); + TrackedObject obj = createDummyTrackedObject(50.0, 1.5, 0.0, 10.0); + + bool result = checkCloseLaneletCondition({0.0, lanelet}, obj, 5.0, M_PI / 4); + EXPECT_TRUE(result); +} + +// 2. Outside lanelet but close +TEST(CheckCloseLaneletConditionTest, OutsideLaneletButClose) +{ + auto lanelet = createDummyStraightLanelet(100.0, 3.0); + TrackedObject obj = createDummyTrackedObject(5.0, 50.0, 0.0, 10.0); + + bool result = checkCloseLaneletCondition({3.0, lanelet}, obj, 5.0, M_PI / 4); + EXPECT_TRUE(result); +} + +// 3. Outside lanelet and far +TEST(CheckCloseLaneletConditionTest, OutsideLaneletAndFar) +{ + auto lanelet = createDummyStraightLanelet(100.0, 3.0); + TrackedObject obj = createDummyTrackedObject(10.0, 50.0, 0.0, 10.0); + + bool result = checkCloseLaneletCondition({10.0, lanelet}, obj, 5.0, M_PI / 4); + EXPECT_FALSE(result); +} + +// 4. Inside but has multiple angle difference and velocity conditions +TEST(CheckCloseLaneletConditionTest, AngleDifferenceTooLarge) +{ + auto lanelet = createDummyStraightLanelet(100.0, 3.0); + constexpr double eps = 1e-6; + // 1. forward velocity and angle difference is 0 + const TrackedObject obj1_1 = createDummyTrackedObject(50.0, 1.5, 0.0, 10.0); + const TrackedObject obj1_2 = createDummyTrackedObject(50.0, 1.5, eps, 10.0); + const TrackedObject obj1_3 = createDummyTrackedObject(50.0, 1.5, -eps, 10.0); + // 2. forward velocity and angle difference is Inverse + const TrackedObject obj2_1 = createDummyTrackedObject(50.0, 1.5, M_PI, 10.0); + const TrackedObject obj2_2 = createDummyTrackedObject(50.0, 1.5, M_PI + eps, 10.0); + const TrackedObject obj2_3 = createDummyTrackedObject(50.0, 1.5, M_PI - eps, 10.0); + // 3. backward velocity and angle difference is 0 + const TrackedObject obj3_1 = createDummyTrackedObject(50.0, 1.5, M_PI, -10.0); + const TrackedObject obj3_2 = createDummyTrackedObject(50.0, 1.5, M_PI + eps, -10.0); + const TrackedObject obj3_3 = createDummyTrackedObject(50.0, 1.5, M_PI - eps, -10.0); + // 4. backward velocity and angle difference is Inverse + const TrackedObject obj4_1 = createDummyTrackedObject(50.0, 1.5, 0.0, -10.0); + const TrackedObject obj4_2 = createDummyTrackedObject(50.0, 1.5, eps, -10.0); + const TrackedObject obj4_3 = createDummyTrackedObject(50.0, 1.5, -eps, -10.0); + + // 1 and 3 should be true, 2 and 4 should be false + EXPECT_TRUE(checkCloseLaneletCondition({0.0, lanelet}, obj1_1, 5.0, M_PI / 4)); + EXPECT_TRUE(checkCloseLaneletCondition({0.0, lanelet}, obj1_2, 5.0, M_PI / 4)); + EXPECT_TRUE(checkCloseLaneletCondition({0.0, lanelet}, obj1_3, 5.0, M_PI / 4)); + EXPECT_TRUE(checkCloseLaneletCondition({0.0, lanelet}, obj3_1, 5.0, M_PI / 4)); + EXPECT_TRUE(checkCloseLaneletCondition({0.0, lanelet}, obj3_2, 5.0, M_PI / 4)); + EXPECT_TRUE(checkCloseLaneletCondition({0.0, lanelet}, obj3_3, 5.0, M_PI / 4)); + + EXPECT_FALSE(checkCloseLaneletCondition({0.0, lanelet}, obj2_1, 5.0, M_PI / 4)); + EXPECT_FALSE(checkCloseLaneletCondition({0.0, lanelet}, obj2_2, 5.0, M_PI / 4)); + EXPECT_FALSE(checkCloseLaneletCondition({0.0, lanelet}, obj2_3, 5.0, M_PI / 4)); + EXPECT_FALSE(checkCloseLaneletCondition({0.0, lanelet}, obj4_1, 5.0, M_PI / 4)); + EXPECT_FALSE(checkCloseLaneletCondition({0.0, lanelet}, obj4_2, 5.0, M_PI / 4)); + EXPECT_FALSE(checkCloseLaneletCondition({0.0, lanelet}, obj4_3, 5.0, M_PI / 4)); +} diff --git a/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp b/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp index c7f2bb5bdc60d..084e939ff40a9 100644 --- a/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp +++ b/perception/radar_tracks_msgs_converter/src/radar_tracks_msgs_converter_node/radar_tracks_msgs_converter_node.cpp @@ -87,7 +87,7 @@ RadarTracksMsgsConverterNode::RadarTracksMsgsConverterNode(const rclcpp::NodeOpt // Subscriber sub_radar_ = create_subscription( - "~/input/radar_objects", rclcpp::QoS{1}, + "~/input/radar_objects", rclcpp::QoS{1}.best_effort(), std::bind(&RadarTracksMsgsConverterNode::onRadarTracks, this, _1)); sub_odometry_ = create_subscription( "~/input/odometry", rclcpp::QoS{1}, diff --git a/perception/raindrop_cluster_filter/CMakeLists.txt b/perception/raindrop_cluster_filter/CMakeLists.txt new file mode 100644 index 0000000000000..a867bc740317b --- /dev/null +++ b/perception/raindrop_cluster_filter/CMakeLists.txt @@ -0,0 +1,31 @@ +cmake_minimum_required(VERSION 3.8) +project(raindrop_cluster_filter) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() +# find dependencies +find_package(autoware_cmake REQUIRED) +autoware_package() + +# Targets +ament_auto_add_library(low_intensity_cluster_filter SHARED + src/low_intensity_cluster_filter.cpp +) + +rclcpp_components_register_node(low_intensity_cluster_filter + PLUGIN "low_intensity_cluster_filter::LowIntensityClusterFilter" + EXECUTABLE low_intensity_cluster_filter_node) + + +if(BUILD_TESTING) + list(APPEND AMENT_LINT_AUTO_EXCLUDE ament_cmake_uncrustify) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_auto_package( + INSTALL_TO_SHARE + launch + config +) diff --git a/perception/raindrop_cluster_filter/config/low_intensity_cluster_filter.param.yaml b/perception/raindrop_cluster_filter/config/low_intensity_cluster_filter.param.yaml new file mode 100644 index 0000000000000..5c0892aa34721 --- /dev/null +++ b/perception/raindrop_cluster_filter/config/low_intensity_cluster_filter.param.yaml @@ -0,0 +1,17 @@ +/**: + ros__parameters: + intensity_threshold: 1.0 + existence_probability_threshold: 0.2 + max_x: 60.0 + min_x: -20.0 + max_y: 20.0 + min_y: -20.0 + filter_target_label: + UNKNOWN: true + CAR: false + TRUCK: false + BUS: false + TRAILER: false + MOTORCYCLE: false + BICYCLE: false + PEDESTRIAN: false diff --git a/perception/raindrop_cluster_filter/include/raindrop_cluster_filter/low_intensity_cluster_filter/low_intensity_cluster_filter.hpp b/perception/raindrop_cluster_filter/include/raindrop_cluster_filter/low_intensity_cluster_filter/low_intensity_cluster_filter.hpp new file mode 100644 index 0000000000000..86a790e208012 --- /dev/null +++ b/perception/raindrop_cluster_filter/include/raindrop_cluster_filter/low_intensity_cluster_filter/low_intensity_cluster_filter.hpp @@ -0,0 +1,78 @@ +// 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 RAINDROP_CLUSTER_FILTER__LOW_INTENSITY_CLUSTER_FILTER__LOW_INTENSITY_CLUSTER_FILTER_HPP_ +#define RAINDROP_CLUSTER_FILTER__LOW_INTENSITY_CLUSTER_FILTER__LOW_INTENSITY_CLUSTER_FILTER_HPP_ + +#include "detected_object_validation/utils/utils.hpp" + +#include +#include +#include + +#include + +#include +#include +// #include +#include + +#include +#include + +namespace low_intensity_cluster_filter +{ + +class LowIntensityClusterFilter : public rclcpp::Node +{ +public: + explicit LowIntensityClusterFilter(const rclcpp::NodeOptions & node_options); + +private: + void objectCallback( + const tier4_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_msg); + bool isValidatedCluster(const sensor_msgs::msg::PointCloud2 & cluster); + + rclcpp::Publisher::SharedPtr object_pub_; + rclcpp::Subscription::SharedPtr + object_sub_; + + tf2_ros::Buffer tf_buffer_; + tf2_ros::TransformListener tf_listener_; + double intensity_threshold_; + double existence_probability_threshold_; + double max_x_; + double min_x_; + double max_y_; + double min_y_; + + double max_x_transformed_; + double min_x_transformed_; + double max_y_transformed_; + double min_y_transformed_; + // Eigen::Vector4f min_boundary_transformed_; + // Eigen::Vector4f max_boundary_transformed_; + bool is_validation_range_transformed_ = false; + const std::string base_link_frame_id_ = "base_link"; + utils::FilterTargetLabel filter_target_; + + // debugger + std::unique_ptr> stop_watch_ptr_{ + nullptr}; + std::unique_ptr debug_publisher_ptr_{nullptr}; +}; + +} // namespace low_intensity_cluster_filter + +#endif // RAINDROP_CLUSTER_FILTER__LOW_INTENSITY_CLUSTER_FILTER__LOW_INTENSITY_CLUSTER_FILTER_HPP_ diff --git a/perception/raindrop_cluster_filter/launch/low_intensity_cluster_filter.launch.xml b/perception/raindrop_cluster_filter/launch/low_intensity_cluster_filter.launch.xml new file mode 100644 index 0000000000000..9af4ad47055f9 --- /dev/null +++ b/perception/raindrop_cluster_filter/launch/low_intensity_cluster_filter.launch.xml @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/perception/raindrop_cluster_filter/package.xml b/perception/raindrop_cluster_filter/package.xml new file mode 100644 index 0000000000000..492b789239d54 --- /dev/null +++ b/perception/raindrop_cluster_filter/package.xml @@ -0,0 +1,36 @@ + + + + raindrop_cluster_filter + 0.1.0 + The ROS 2 filter cluster package + Yukihiro Saito + Dai Nguyen + Yoshi Ri + Apache License 2.0 + Dai Nguyen + + ament_cmake + autoware_cmake + detected_object_validation + lanelet2_extension + message_filters + nav_msgs + pcl_conversions + pcl_ros + rclcpp + rclcpp_components + sensor_msgs + tf2 + tf2_eigen + tf2_ros + tier4_autoware_utils + tier4_perception_msgs + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/perception/raindrop_cluster_filter/raindrop_cluster_filter.md b/perception/raindrop_cluster_filter/raindrop_cluster_filter.md new file mode 100644 index 0000000000000..175bbd00a93ea --- /dev/null +++ b/perception/raindrop_cluster_filter/raindrop_cluster_filter.md @@ -0,0 +1,54 @@ +# low_intensity_cluster_filter + +## Purpose + +The `low_intensity_cluster_filter` is a node that filters clusters based on the intensity of their pointcloud. + +Mainly this focuses on filtering out unknown objects with very low intensity pointcloud, such as fail detection of unknown objects caused by raindrop or water splash from ego or other fast moving vehicles. + +## Inner-workings / Algorithms + +## Inputs / Outputs + +### Input + +| Name | Type | Description | +| -------------- | -------------------------------------------------------- | ---------------------- | +| `input/object` | `tier4_perception_msgs::msg::DetectedObjectsWithFeature` | input detected objects | + +### Output + +| Name | Type | Description | +| --------------- | -------------------------------------------------------- | ------------------------- | +| `output/object` | `tier4_perception_msgs::msg::DetectedObjectsWithFeature` | filtered detected objects | + +## Parameters + +### Core Parameters + +| Name | Type | Default Value | Description | +| --------------------------------- | ----- | ------------------------------------------------------- | --------------------------------------------- | +| `filter_target_label.UNKNOWN` | bool | false | If true, unknown objects are filtered. | +| `filter_target_label.CAR` | bool | false | If true, car objects are filtered. | +| `filter_target_label.TRUCK` | bool | false | If true, truck objects are filtered. | +| `filter_target_label.BUS` | bool | false | If true, bus objects are filtered. | +| `filter_target_label.TRAILER` | bool | false | If true, trailer objects are filtered. | +| `filter_target_label.MOTORCYCLE` | bool | false | If true, motorcycle objects are filtered. | +| `filter_target_label.BICYCLE` | bool | false | If true, bicycle objects are filtered. | +| `filter_target_label.PEDESTRIAN` | bool | false | If true, pedestrian objects are filtered. | +| `max_x` | float | 60.00 | Maximum of x of the filter effective range | +| `min_x` | float | -20.00 | Minimum of x of the filter effective range | +| `max_y` | float | 20.00 | Maximum of y of the filter effective range | +| `min_y` | float | -20.00 | Minium of y of the filter effective range | +| `intensity_threshold` | float | 1.0 | The threshold of average intensity for filter | +| `existence_probability_threshold` | float | The existence probability threshold to apply the filter | + +## Assumptions / Known limits + +## (Optional) Error detection and handling + +## (Optional) Performance characterization + +## (Optional) References/External links + +## (Optional) Future extensions / Unimplemented parts diff --git a/perception/raindrop_cluster_filter/src/low_intensity_cluster_filter.cpp b/perception/raindrop_cluster_filter/src/low_intensity_cluster_filter.cpp new file mode 100644 index 0000000000000..5c47b61eaa0a3 --- /dev/null +++ b/perception/raindrop_cluster_filter/src/low_intensity_cluster_filter.cpp @@ -0,0 +1,141 @@ +// 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 "raindrop_cluster_filter/low_intensity_cluster_filter/low_intensity_cluster_filter.hpp" + +#include +#include + +#include + +#include +namespace low_intensity_cluster_filter +{ +LowIntensityClusterFilter::LowIntensityClusterFilter(const rclcpp::NodeOptions & node_options) +: Node("low_intensity_cluster_filter_node", node_options), + tf_buffer_(this->get_clock()), + tf_listener_(tf_buffer_) +{ + intensity_threshold_ = declare_parameter("intensity_threshold"); + existence_probability_threshold_ = declare_parameter("existence_probability_threshold"); + max_x_ = declare_parameter("max_x"); + min_x_ = declare_parameter("min_x"); + max_y_ = declare_parameter("max_y"); + min_y_ = declare_parameter("min_y"); + + filter_target_.UNKNOWN = declare_parameter("filter_target_label.UNKNOWN"); + filter_target_.CAR = declare_parameter("filter_target_label.CAR"); + filter_target_.TRUCK = declare_parameter("filter_target_label.TRUCK"); + filter_target_.BUS = declare_parameter("filter_target_label.BUS"); + filter_target_.TRAILER = declare_parameter("filter_target_label.TRAILER"); + filter_target_.MOTORCYCLE = declare_parameter("filter_target_label.MOTORCYCLE"); + filter_target_.BICYCLE = declare_parameter("filter_target_label.BICYCLE"); + filter_target_.PEDESTRIAN = declare_parameter("filter_target_label.PEDESTRIAN"); + + using std::placeholders::_1; + // Set publisher/subscriber + object_sub_ = this->create_subscription( + "input/objects", rclcpp::QoS{1}, + std::bind(&LowIntensityClusterFilter::objectCallback, this, _1)); + object_pub_ = this->create_publisher( + "output/objects", rclcpp::QoS{1}); + // initialize debug tool + { + using tier4_autoware_utils::DebugPublisher; + using tier4_autoware_utils::StopWatch; + stop_watch_ptr_ = std::make_unique>(); + debug_publisher_ptr_ = + std::make_unique(this, "low_intensity_cluster_filter_node"); + stop_watch_ptr_->tic("cyclic_time"); + stop_watch_ptr_->tic("processing_time"); + } +} + +void LowIntensityClusterFilter::objectCallback( + const tier4_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_msg) +{ + // Guard + stop_watch_ptr_->toc("processing_time", true); + if (object_pub_->get_subscription_count() < 1) return; + + tier4_perception_msgs::msg::DetectedObjectsWithFeature output_object_msg; + output_object_msg.header = input_msg->header; + geometry_msgs::msg::TransformStamped transform_stamp; + try { + transform_stamp = tf_buffer_.lookupTransform( + input_msg->header.frame_id, base_link_frame_id_, tf2_ros::fromMsg(input_msg->header.stamp)); + } catch (tf2::TransformException & ex) { + RCLCPP_ERROR(get_logger(), "Failed to lookup transform: %s", ex.what()); + return; + } + geometry_msgs::msg::Pose min_range; + min_range.position.x = min_x_; + min_range.position.y = min_y_; + geometry_msgs::msg::Pose max_pose; + max_pose.position.x = max_x_; + max_pose.position.y = max_y_; + auto min_ranged_transformed = tier4_autoware_utils::transformPose(min_range, transform_stamp); + auto max_range_transformed = tier4_autoware_utils::transformPose(max_pose, transform_stamp); + for (const auto & feature_object : input_msg->feature_objects) { + const auto & object = feature_object.object; + const auto & label = object.classification.front().label; + const auto & feature = feature_object.feature; + const auto & cluster = feature.cluster; + const auto existence_probability = object.existence_probability; + const auto & position = object.kinematics.pose_with_covariance.pose.position; + bool is_inside_validation_range = min_ranged_transformed.position.x < position.x && + position.x < max_range_transformed.position.x && + min_ranged_transformed.position.y < position.x && + position.y < max_range_transformed.position.y; + int intensity_index = pcl::getFieldIndex(cluster, "intensity"); + if ( + intensity_index != -1 && filter_target_.isTarget(label) && is_inside_validation_range && + !isValidatedCluster(cluster) && existence_probability < existence_probability_threshold_) { + continue; + } + output_object_msg.feature_objects.emplace_back(feature_object); + } + object_pub_->publish(output_object_msg); + if (debug_publisher_ptr_ && stop_watch_ptr_) { + 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_ptr_->publish( + "debug/cyclic_time_ms", cyclic_time_ms); + debug_publisher_ptr_->publish( + "debug/processing_time_ms", processing_time_ms); + } +} +bool LowIntensityClusterFilter::isValidatedCluster(const sensor_msgs::msg::PointCloud2 & cluster) +{ + double mean_intensity = 0.0; + if (cluster.point_step < 16) { + RCLCPP_WARN(get_logger(), "Invalid point cloud data. point_step is less than 16."); + return true; + } + for (sensor_msgs::PointCloud2ConstIterator iter(cluster, "intensity"); iter != iter.end(); + ++iter) { + mean_intensity += *iter; + } + const size_t num_points = cluster.width * cluster.height; + mean_intensity /= static_cast(num_points); + if (mean_intensity > intensity_threshold_) { + return true; + } + return false; +} + +} // namespace low_intensity_cluster_filter + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(low_intensity_cluster_filter::LowIntensityClusterFilter) diff --git a/perception/shape_estimation/CMakeLists.txt b/perception/shape_estimation/CMakeLists.txt index 8eb7a15b5a885..527c565b91e05 100644 --- a/perception/shape_estimation/CMakeLists.txt +++ b/perception/shape_estimation/CMakeLists.txt @@ -66,3 +66,19 @@ ament_auto_package(INSTALL_TO_SHARE launch config ) + +## Tests +if(BUILD_TESTING) + find_package(ament_cmake_ros REQUIRED) + list(APPEND AMENT_LINT_AUTO_EXCLUDE ament_cmake_uncrustify) + + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + + file(GLOB_RECURSE test_files test/**/*.cpp) + ament_add_ros_isolated_gtest(test_shape_estimation ${test_files}) + + target_link_libraries(test_shape_estimation + shape_estimation_node + ) +endif() diff --git a/perception/shape_estimation/package.xml b/perception/shape_estimation/package.xml index 334b6cc2af123..137d925de6d54 100644 --- a/perception/shape_estimation/package.xml +++ b/perception/shape_estimation/package.xml @@ -12,7 +12,6 @@ autoware_cmake autoware_auto_perception_msgs - builtin_interfaces eigen libopencv-dev libpcl-all-dev @@ -25,6 +24,7 @@ tier4_autoware_utils tier4_perception_msgs + ament_cmake_gtest ament_lint_auto autoware_lint_common diff --git a/perception/shape_estimation/src/node.cpp b/perception/shape_estimation/src/node.cpp index 9d7e8b4d4729d..04a96391ca165 100644 --- a/perception/shape_estimation/src/node.cpp +++ b/perception/shape_estimation/src/node.cpp @@ -61,6 +61,22 @@ ShapeEstimationNode::ShapeEstimationNode(const rclcpp::NodeOptions & node_option published_time_publisher_ = std::make_unique(this); } +static autoware_auto_perception_msgs::msg::ObjectClassification::_label_type get_label( + const autoware_auto_perception_msgs::msg::DetectedObject::_classification_type & classification) +{ + if (classification.empty()) { + return Label::UNKNOWN; + } + return classification.front().label; +} + +static bool label_is_vehicle( + const autoware_auto_perception_msgs::msg::ObjectClassification::_label_type & label) +{ + return Label::CAR == label || Label::TRUCK == label || Label::BUS == label || + Label::TRAILER == label; +} + void ShapeEstimationNode::callback(const DetectedObjectsWithFeature::ConstSharedPtr input_msg) { stop_watch_ptr_->toc("processing_time", true); @@ -76,11 +92,9 @@ void ShapeEstimationNode::callback(const DetectedObjectsWithFeature::ConstShared // Estimate shape for each object and pack msg for (const auto & feature_object : input_msg->feature_objects) { const auto & object = feature_object.object; - const auto & label = object.classification.front().label; + const auto label = get_label(object.classification); + const auto is_vehicle = label_is_vehicle(label); const auto & feature = feature_object.feature; - const bool is_vehicle = Label::CAR == label || Label::TRUCK == label || Label::BUS == label || - Label::TRAILER == label; - // convert ros to pcl pcl::PointCloud::Ptr cluster(new pcl::PointCloud); pcl::fromROSMsg(feature.cluster, *cluster); diff --git a/perception/shape_estimation/test/shape_estimation/test_shape_estimator.cpp b/perception/shape_estimation/test/shape_estimation/test_shape_estimator.cpp new file mode 100644 index 0000000000000..d59cfd11b69df --- /dev/null +++ b/perception/shape_estimation/test/shape_estimation/test_shape_estimator.cpp @@ -0,0 +1,236 @@ + +// 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 "shape_estimation/corrector/corrector.hpp" +#include "shape_estimation/filter/filter.hpp" +#include "shape_estimation/model/model.hpp" +#include "shape_estimation/shape_estimator.hpp" + +#include +#include + +namespace +{ +double yawFromQuaternion(const geometry_msgs::msg::Quaternion & q) +{ + return atan2(2.0 * (q.w * q.z + q.x * q.y), 1.0 - 2.0 * (q.y * q.y + q.z * q.z)); +} + +double deg2rad(const double deg) +{ + return deg / 180.0 * M_PI; +} + +pcl::PointCloud createLShapeCluster( + const double length, const double width, const double height, const double yaw, + const double offset_x, const double offset_y) +{ + pcl::PointCloud cluster; + for (double x = -length / 2; x < length / 2; x += 0.4) { + cluster.push_back(pcl::PointXYZ(x, width / 2, 0.0)); + } + for (double y = -width / 2; y < width / 2; y += 0.2) { + cluster.push_back(pcl::PointXYZ(-length / 2, y, 0.0)); + } + cluster.push_back(pcl::PointXYZ(length / 2, -width / 2, 0.0)); + cluster.push_back(pcl::PointXYZ(length / 2, width / 2, 0.0)); + cluster.push_back(pcl::PointXYZ(-length / 2, -width / 2, 0.0)); + cluster.push_back(pcl::PointXYZ(-length / 2, width / 2, 0.0)); + cluster.push_back(pcl::PointXYZ(0.0, 0.0, height)); + + for (auto & point : cluster) { + const double x = point.x; + const double y = point.y; + // rotate + point.x = x * cos(yaw) - y * sin(yaw); + point.y = x * sin(yaw) + y * cos(yaw); + // offset + point.x += offset_x; + point.y += offset_y; + } + + return cluster; +} +} // namespace + +// test BoundingBoxShapeModel +// 1. base case +TEST(BoundingBoxShapeModel, test_estimateShape) +{ + // Generate BoundingBoxShapeModel + BoundingBoxShapeModel bbox_shape_model = BoundingBoxShapeModel(); + + // Generate cluster + const double length = 4.0; + const double width = 2.0; + const double height = 1.0; + + pcl::PointCloud cluster = + createLShapeCluster(length, width, height, 0.0, 0.0, 0.0); + + // Generate shape and pose output + autoware_auto_perception_msgs::msg::Shape shape_output; + geometry_msgs::msg::Pose pose_output; + + // Test estimateShape + const bool result = bbox_shape_model.estimate(cluster, shape_output, pose_output); + EXPECT_TRUE(result); + + // Check shape_output + EXPECT_EQ(shape_output.type, autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX); + EXPECT_NEAR(shape_output.dimensions.x, length, length * 0.1); + EXPECT_NEAR(shape_output.dimensions.y, width, width * 0.1); + EXPECT_NEAR(shape_output.dimensions.z, height, height * 0.1); + + // Check pose_output + EXPECT_NEAR(pose_output.position.x, 0.0, 1e-2); + EXPECT_NEAR(pose_output.position.y, 0.0, 1e-2); + EXPECT_NEAR(pose_output.position.z, height / 2, 1e-2); + + // transform quaternion to yaw + const double pose_output_yaw = yawFromQuaternion(pose_output.orientation); + EXPECT_NEAR(pose_output_yaw, 0, 1e-3); +} + +// 2. rotated case +TEST(BoundingBoxShapeModel, test_estimateShape_rotated) +{ + // Generate cluster + const double length = 4.0; + const double width = 2.0; + const double height = 1.0; + const double yaw = deg2rad(30.0); + const double offset_x = 10.0; + const double offset_y = 1.0; + pcl::PointCloud cluster = + createLShapeCluster(length, width, height, yaw, offset_x, offset_y); + + const auto ref_yaw_info = + ReferenceYawInfo{static_cast(yaw), static_cast(deg2rad(10.0))}; + const bool use_boost_bbox_optimizer = true; + // Generate BoundingBoxShapeModel + BoundingBoxShapeModel bbox_shape_model = + BoundingBoxShapeModel(ref_yaw_info, use_boost_bbox_optimizer); + + // Generate shape and pose output + autoware_auto_perception_msgs::msg::Shape shape_output; + geometry_msgs::msg::Pose pose_output; + + // Test estimateShape + const bool result = bbox_shape_model.estimate(cluster, shape_output, pose_output); + EXPECT_TRUE(result); + + // Check shape_output + EXPECT_EQ(shape_output.type, autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX); + EXPECT_NEAR(shape_output.dimensions.x, length, length * 0.1); + EXPECT_NEAR(shape_output.dimensions.y, width, width * 0.1); + EXPECT_NEAR(shape_output.dimensions.z, height, height * 0.1); + + // Check pose_output + EXPECT_NEAR(pose_output.position.x, offset_x, 1.0); + EXPECT_NEAR(pose_output.position.y, offset_y, 1.0); + EXPECT_NEAR(pose_output.position.z, height / 2, 1.0); + + // transform quaternion to yaw + const double pose_output_yaw = yawFromQuaternion(pose_output.orientation); + EXPECT_NEAR(pose_output_yaw, yaw, deg2rad(15.0)); +} + +// test CylinderShapeModel +TEST(CylinderShapeModel, test_estimateShape) +{ + // Generate CylinderShapeModel + CylinderShapeModel cylinder_shape_model = CylinderShapeModel(); + + // Generate cluster + pcl::PointCloud cluster = createLShapeCluster(4.0, 2.0, 1.0, 0.0, 0.0, 0.0); + // Generate shape and pose output + autoware_auto_perception_msgs::msg::Shape shape_output; + geometry_msgs::msg::Pose pose_output; + + // Test estimateShape + const bool result = cylinder_shape_model.estimate(cluster, shape_output, pose_output); + EXPECT_TRUE(result); +} + +// test ConvexHullShapeModel +TEST(ConvexHullShapeModel, test_estimateShape) +{ + // Generate ConvexHullShapeModel + ConvexHullShapeModel convex_hull_shape_model = ConvexHullShapeModel(); + + // Generate cluster + pcl::PointCloud cluster = createLShapeCluster(2.0, 1.0, 1.0, 0.0, 0.0, 0.0); + + // Generate shape and pose output + autoware_auto_perception_msgs::msg::Shape shape_output; + geometry_msgs::msg::Pose pose_output; + + // Test estimateShape + const bool result = convex_hull_shape_model.estimate(cluster, shape_output, pose_output); + EXPECT_TRUE(result); +} + +// test ShapeEstimator +TEST(ShapeEstimator, test_estimateShapeAndPose) +{ + // Generate cluster + double length = 4.0; + double width = 2.0; + double height = 1.0; + const double yaw = deg2rad(60.0); + const double offset_x = 6.0; + const double offset_y = -2.0; + pcl::PointCloud cluster = + createLShapeCluster(length, width, height, yaw, offset_x, offset_y); + + // Generate ShapeEstimator + const bool use_corrector = true; + const bool use_filter = true; + const bool use_boost_bbox_optimizer = true; + ShapeEstimator shape_estimator = + ShapeEstimator(use_corrector, use_filter, use_boost_bbox_optimizer); + + // Generate ref_yaw_info + boost::optional ref_yaw_info = boost::none; + boost::optional ref_shape_size_info = boost::none; + + ref_yaw_info = ReferenceYawInfo{static_cast(yaw), static_cast(deg2rad(10.0))}; + const auto label = autoware_auto_perception_msgs::msg::ObjectClassification::CAR; + + // Generate shape and pose output + autoware_auto_perception_msgs::msg::Shape shape_output; + geometry_msgs::msg::Pose pose_output; + + // Test estimateShapeAndPose + const bool result = shape_estimator.estimateShapeAndPose( + label, cluster, ref_yaw_info, ref_shape_size_info, shape_output, pose_output); + EXPECT_TRUE(result); + + // Check shape_output + EXPECT_EQ(shape_output.type, autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX); + EXPECT_NEAR(shape_output.dimensions.x, length, length * 0.1); + EXPECT_NEAR(shape_output.dimensions.y, width, width * 0.1); + EXPECT_NEAR(shape_output.dimensions.z, height, height * 0.1); + + // Check pose_output + EXPECT_NEAR(pose_output.position.x, offset_x, 1.0); + EXPECT_NEAR(pose_output.position.y, offset_y, 1.0); + EXPECT_NEAR(pose_output.position.z, height / 2, 1.0); + + // transform quaternion to yaw + const double pose_output_yaw = yawFromQuaternion(pose_output.orientation); + EXPECT_NEAR(pose_output_yaw, yaw, deg2rad(15.0)); +} diff --git a/localization/yabloc/yabloc_common/src/ll2_decomposer/ll2_decomposer_node.cpp b/perception/shape_estimation/test/test_shape_estimation.cpp similarity index 78% rename from localization/yabloc/yabloc_common/src/ll2_decomposer/ll2_decomposer_node.cpp rename to perception/shape_estimation/test/test_shape_estimation.cpp index 692f6a5da0913..4c8ad7dd25916 100644 --- a/localization/yabloc/yabloc_common/src/ll2_decomposer/ll2_decomposer_node.cpp +++ b/perception/shape_estimation/test/test_shape_estimation.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 TIER IV, Inc. +// 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. @@ -12,12 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "yabloc_common/ll2_decomposer/ll2_decomposer.hpp" +#include + +#include int main(int argc, char * argv[]) { + testing::InitGoogleTest(&argc, argv); rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()); + bool result = RUN_ALL_TESTS(); rclcpp::shutdown(); - return 0; + return result; } diff --git a/perception/tensorrt_yolox/include/tensorrt_yolox/tensorrt_yolox_node.hpp b/perception/tensorrt_yolox/include/tensorrt_yolox/tensorrt_yolox_node.hpp index 9b440f1dbdfec..fc396ae4b3473 100644 --- a/perception/tensorrt_yolox/include/tensorrt_yolox/tensorrt_yolox_node.hpp +++ b/perception/tensorrt_yolox/include/tensorrt_yolox/tensorrt_yolox_node.hpp @@ -19,6 +19,8 @@ #include #include #include +#include +#include #include #include @@ -61,6 +63,8 @@ class TrtYoloXNode : public rclcpp::Node LabelMap label_map_; std::unique_ptr trt_yolox_; + std::unique_ptr> stop_watch_ptr_; + std::unique_ptr debug_publisher_; }; } // namespace tensorrt_yolox diff --git a/perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp b/perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp index af435ce6efe83..93380b95680c2 100644 --- a/perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp +++ b/perception/tensorrt_yolox/src/tensorrt_yolox_node.cpp @@ -29,6 +29,14 @@ namespace tensorrt_yolox TrtYoloXNode::TrtYoloXNode(const rclcpp::NodeOptions & node_options) : Node("tensorrt_yolox", node_options) { + { + stop_watch_ptr_ = + std::make_unique>(); + debug_publisher_ = + std::make_unique(this, "tensorrt_yolox"); + stop_watch_ptr_->tic("cyclic_time"); + stop_watch_ptr_->tic("processing_time"); + } using std::placeholders::_1; using std::chrono_literals::operator""ms; @@ -132,6 +140,7 @@ void TrtYoloXNode::onConnect() void TrtYoloXNode::onImage(const sensor_msgs::msg::Image::ConstSharedPtr msg) { + stop_watch_ptr_->toc("processing_time", true); tier4_perception_msgs::msg::DetectedObjectsWithFeature out_objects; cv_bridge::CvImagePtr in_image_ptr; @@ -173,6 +182,22 @@ void TrtYoloXNode::onImage(const sensor_msgs::msg::Image::ConstSharedPtr msg) out_objects.header = msg->header; objects_pub_->publish(out_objects); + + if (debug_publisher_) { + const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); + const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); + const double pipeline_latency_ms = + std::chrono::duration( + std::chrono::nanoseconds( + (this->get_clock()->now() - out_objects.header.stamp).nanoseconds())) + .count(); + debug_publisher_->publish( + "debug/cyclic_time_ms", cyclic_time_ms); + debug_publisher_->publish( + "debug/processing_time_ms", processing_time_ms); + debug_publisher_->publish( + "debug/pipeline_latency_ms", pipeline_latency_ms); + } } bool TrtYoloXNode::readLabelFile(const std::string & label_path) 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/data_association/data_association.cpp b/perception/tracking_object_merger/src/data_association/data_association.cpp index e7ab6077250f8..7cd7d532d07f5 100644 --- a/perception/tracking_object_merger/src/data_association/data_association.cpp +++ b/perception/tracking_object_merger/src/data_association/data_association.cpp @@ -180,13 +180,6 @@ double DataAssociation::calcScoreBetweenObjects( const std::uint8_t object0_label = object_recognition_utils::getHighestProbLabel(object0.classification); - std::vector tracker_pose = { - object1.kinematics.pose_with_covariance.pose.position.x, - object1.kinematics.pose_with_covariance.pose.position.y}; - std::vector measurement_pose = { - object0.kinematics.pose_with_covariance.pose.position.x, - object0.kinematics.pose_with_covariance.pose.position.y}; - double score = 0.0; if (can_assign_matrix_(object1_label, object0_label)) { const double max_dist = max_dist_matrix_(object1_label, object0_label); 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( 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_classifier/src/cnn_classifier.cpp b/perception/traffic_light_classifier/src/cnn_classifier.cpp index cd266ac25b822..d6ba81041c6f8 100644 --- a/perception/traffic_light_classifier/src/cnn_classifier.cpp +++ b/perception/traffic_light_classifier/src/cnn_classifier.cpp @@ -108,7 +108,7 @@ bool CNNClassifier::getTrafficSignals( void CNNClassifier::outputDebugImage( cv::Mat & debug_image, const tier4_perception_msgs::msg::TrafficLight & traffic_signal) { - float probability; + float probability = 0.0f; std::string label; for (std::size_t i = 0; i < traffic_signal.elements.size(); i++) { auto light = traffic_signal.elements.at(i); 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_occlusion_predictor/package.xml b/perception/traffic_light_occlusion_predictor/package.xml index 49a67d68057d9..daf14ba4147c2 100644 --- a/perception/traffic_light_occlusion_predictor/package.xml +++ b/perception/traffic_light_occlusion_predictor/package.xml @@ -12,7 +12,6 @@ autoware_cmake - autoware_auto_geometry autoware_auto_mapping_msgs geometry_msgs image_geometry 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/planning/.pages b/planning/.pages index 942a5a0b32158..4514894605bbc 100644 --- a/planning/.pages +++ b/planning/.pages @@ -18,7 +18,7 @@ nav: - 'Side Shift': planning/behavior_path_side_shift_module - 'Start Planner': planning/behavior_path_start_planner_module - 'Behavior Velocity Planner': - - 'About Behavior Velocity': planning/behavior_velocity_planner + - 'About Behavior Velocity': planning/autoware_behavior_velocity_planner - 'Template for Custom Module': planning/behavior_velocity_template_module - 'Available Module': - 'Blind Spot': planning/behavior_velocity_blind_spot_module @@ -63,11 +63,15 @@ nav: - 'Surround Obstacle Checker': - 'About Surround Obstacle Checker': planning/surround_obstacle_checker - 'About Surround Obstacle Checker (Japanese)': planning/surround_obstacle_checker/surround_obstacle_checker-design.ja + - 'Motion Velocity Planner': + - 'About Motion Velocity Planner': planning/autoware_motion_velocity_planner_node/ + - 'Available Modules': + - 'Out of Lane': planning/autoware_motion_velocity_planner_out_of_lane_module/ - 'Motion Velocity Smoother': - '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 @@ -80,5 +84,6 @@ nav: - 'About Planning Debug Tools': https://github.com/autowarefoundation/autoware_tools/tree/main/planning/planning_debug_tools - 'Stop Reason Visualizer': https://github.com/autowarefoundation/autoware_tools/blob/main/planning/planning_debug_tools/doc-stop-reason-visualizer.md - 'Planning Test Utils': planning/planning_test_utils + - 'Planning Test Manager': planning/autoware_planning_test_manager - 'Planning Topic Converter': planning/planning_topic_converter - 'Planning Validator': planning/planning_validator diff --git a/planning/behavior_path_dynamic_avoidance_module/CMakeLists.txt b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/CMakeLists.txt similarity index 89% rename from planning/behavior_path_dynamic_avoidance_module/CMakeLists.txt rename to planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/CMakeLists.txt index 98874b8923324..e7df28307e754 100644 --- a/planning/behavior_path_dynamic_avoidance_module/CMakeLists.txt +++ b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(behavior_path_dynamic_avoidance_module) +project(autoware_behavior_path_dynamic_obstacle_avoidance_module) find_package(autoware_cmake REQUIRED) autoware_package() diff --git a/planning/behavior_path_dynamic_avoidance_module/README.md b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/README.md similarity index 99% rename from planning/behavior_path_dynamic_avoidance_module/README.md rename to planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/README.md index b8af767afd9a5..e0fec11d166a6 100644 --- a/planning/behavior_path_dynamic_avoidance_module/README.md +++ b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/README.md @@ -1,4 +1,4 @@ -# Dynamic avoidance design +# Avoidance module for dynamic objects This module is under development. diff --git a/planning/behavior_path_dynamic_avoidance_module/config/dynamic_avoidance.param.yaml b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/config/dynamic_obstacle_avoidance.param.yaml similarity index 100% rename from planning/behavior_path_dynamic_avoidance_module/config/dynamic_avoidance.param.yaml rename to planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/config/dynamic_obstacle_avoidance.param.yaml diff --git a/planning/behavior_path_dynamic_avoidance_module/image/2024-04-18_15-13-01.png b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/image/2024-04-18_15-13-01.png similarity index 100% rename from planning/behavior_path_dynamic_avoidance_module/image/2024-04-18_15-13-01.png rename to planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/image/2024-04-18_15-13-01.png diff --git a/planning/behavior_path_dynamic_avoidance_module/image/2024-04-18_15-32-03.png b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/image/2024-04-18_15-32-03.png similarity index 100% rename from planning/behavior_path_dynamic_avoidance_module/image/2024-04-18_15-32-03.png rename to planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/image/2024-04-18_15-32-03.png diff --git a/planning/behavior_path_dynamic_avoidance_module/image/drivable_area_extraction_width.drawio.svg b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/image/drivable_area_extraction_width.drawio.svg similarity index 100% rename from planning/behavior_path_dynamic_avoidance_module/image/drivable_area_extraction_width.drawio.svg rename to planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/image/drivable_area_extraction_width.drawio.svg diff --git a/planning/behavior_path_dynamic_avoidance_module/image/image-20230807-151945.png b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/image/image-20230807-151945.png similarity index 100% rename from planning/behavior_path_dynamic_avoidance_module/image/image-20230807-151945.png rename to planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/image/image-20230807-151945.png diff --git a/planning/behavior_path_dynamic_avoidance_module/image/image-20230807-152835.png b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/image/image-20230807-152835.png similarity index 100% rename from planning/behavior_path_dynamic_avoidance_module/image/image-20230807-152835.png rename to planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/image/image-20230807-152835.png diff --git a/planning/behavior_path_dynamic_avoidance_module/image/image-20230808-095936.png b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/image/image-20230808-095936.png similarity index 100% rename from planning/behavior_path_dynamic_avoidance_module/image/image-20230808-095936.png rename to planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/image/image-20230808-095936.png diff --git a/planning/behavior_path_dynamic_avoidance_module/image/image-20230808-152853.png b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/image/image-20230808-152853.png similarity index 100% rename from planning/behavior_path_dynamic_avoidance_module/image/image-20230808-152853.png rename to planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/image/image-20230808-152853.png diff --git a/planning/behavior_path_dynamic_avoidance_module/image/opposite_directional_object.svg b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/image/opposite_directional_object.svg similarity index 100% rename from planning/behavior_path_dynamic_avoidance_module/image/opposite_directional_object.svg rename to planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/image/opposite_directional_object.svg diff --git a/planning/behavior_path_dynamic_avoidance_module/image/same_directional_object.svg b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/image/same_directional_object.svg similarity index 100% rename from planning/behavior_path_dynamic_avoidance_module/image/same_directional_object.svg rename to planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/image/same_directional_object.svg diff --git a/planning/behavior_path_dynamic_avoidance_module/include/behavior_path_dynamic_avoidance_module/manager.hpp b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware_behavior_path_dynamic_obstacle_avoidance_module/manager.hpp similarity index 69% rename from planning/behavior_path_dynamic_avoidance_module/include/behavior_path_dynamic_avoidance_module/manager.hpp rename to planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware_behavior_path_dynamic_obstacle_avoidance_module/manager.hpp index c2c17c4e55c1e..caf0544b0852e 100644 --- a/planning/behavior_path_dynamic_avoidance_module/include/behavior_path_dynamic_avoidance_module/manager.hpp +++ b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware_behavior_path_dynamic_obstacle_avoidance_module/manager.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_DYNAMIC_AVOIDANCE_MODULE__MANAGER_HPP_ -#define BEHAVIOR_PATH_DYNAMIC_AVOIDANCE_MODULE__MANAGER_HPP_ +#ifndef AUTOWARE_BEHAVIOR_PATH_DYNAMIC_OBSTACLE_AVOIDANCE_MODULE__MANAGER_HPP_ +#define AUTOWARE_BEHAVIOR_PATH_DYNAMIC_OBSTACLE_AVOIDANCE_MODULE__MANAGER_HPP_ -#include "behavior_path_dynamic_avoidance_module/scene.hpp" +#include "autoware_behavior_path_dynamic_obstacle_avoidance_module/scene.hpp" #include "behavior_path_planner_common/interface/scene_module_manager_interface.hpp" #include @@ -28,16 +28,19 @@ namespace behavior_path_planner { -class DynamicAvoidanceModuleManager : public SceneModuleManagerInterface +class DynamicObstacleAvoidanceModuleManager : public SceneModuleManagerInterface { public: - DynamicAvoidanceModuleManager() : SceneModuleManagerInterface{"dynamic_avoidance"} {} + DynamicObstacleAvoidanceModuleManager() + : SceneModuleManagerInterface{"dynamic_obstacle_avoidance"} + { + } void init(rclcpp::Node * node) override; std::unique_ptr createNewSceneModuleInstance() override { - return std::make_unique( + return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, objects_of_interest_marker_interface_ptr_map_); } @@ -52,4 +55,4 @@ class DynamicAvoidanceModuleManager : public SceneModuleManagerInterface } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_DYNAMIC_AVOIDANCE_MODULE__MANAGER_HPP_ +#endif // AUTOWARE_BEHAVIOR_PATH_DYNAMIC_OBSTACLE_AVOIDANCE_MODULE__MANAGER_HPP_ diff --git a/planning/behavior_path_dynamic_avoidance_module/include/behavior_path_dynamic_avoidance_module/scene.hpp b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware_behavior_path_dynamic_obstacle_avoidance_module/scene.hpp similarity index 97% rename from planning/behavior_path_dynamic_avoidance_module/include/behavior_path_dynamic_avoidance_module/scene.hpp rename to planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware_behavior_path_dynamic_obstacle_avoidance_module/scene.hpp index 353a5fab92032..22152911b46b2 100644 --- a/planning/behavior_path_dynamic_avoidance_module/include/behavior_path_dynamic_avoidance_module/scene.hpp +++ b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware_behavior_path_dynamic_obstacle_avoidance_module/scene.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_DYNAMIC_AVOIDANCE_MODULE__SCENE_HPP_ -#define BEHAVIOR_PATH_DYNAMIC_AVOIDANCE_MODULE__SCENE_HPP_ +#ifndef AUTOWARE_BEHAVIOR_PATH_DYNAMIC_OBSTACLE_AVOIDANCE_MODULE__SCENE_HPP_ +#define AUTOWARE_BEHAVIOR_PATH_DYNAMIC_OBSTACLE_AVOIDANCE_MODULE__SCENE_HPP_ #include "behavior_path_planner_common/interface/scene_module_interface.hpp" #include "tier4_autoware_utils/system/stop_watch.hpp" @@ -164,7 +164,7 @@ struct LatFeasiblePaths std::vector left_path; std::vector right_path; }; -class DynamicAvoidanceModule : public SceneModuleInterface +class DynamicObstacleAvoidanceModule : public SceneModuleInterface { public: struct DynamicAvoidanceObject @@ -336,7 +336,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface std::string reason{""}; }; - DynamicAvoidanceModule( + DynamicObstacleAvoidanceModule( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, @@ -444,8 +444,8 @@ class DynamicAvoidanceModule : public SceneModuleInterface getLogger(), parameters_->enable_debug_info, reason_text.c_str(), obj_uuid.c_str()); } - std::vector target_objects_; - // std::vector prev_target_objects_; + std::vector target_objects_; + // std::vector prev_target_objects_; std::optional> prev_input_ref_path_points_{std::nullopt}; std::optional> ref_path_before_lane_change_{std::nullopt}; std::shared_ptr parameters_; @@ -458,4 +458,4 @@ class DynamicAvoidanceModule : public SceneModuleInterface }; } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_DYNAMIC_AVOIDANCE_MODULE__SCENE_HPP_ +#endif // AUTOWARE_BEHAVIOR_PATH_DYNAMIC_OBSTACLE_AVOIDANCE_MODULE__SCENE_HPP_ diff --git a/planning/behavior_path_dynamic_avoidance_module/package.xml b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/package.xml similarity index 89% rename from planning/behavior_path_dynamic_avoidance_module/package.xml rename to planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/package.xml index 11792a15b2cd2..9b64069eddafd 100644 --- a/planning/behavior_path_dynamic_avoidance_module/package.xml +++ b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/package.xml @@ -1,9 +1,9 @@ - behavior_path_dynamic_avoidance_module + autoware_behavior_path_dynamic_obstacle_avoidance_module 0.1.0 - The behavior_path_dynamic_avoidance_module package + The autoware_behavior_path_dynamic_obstacle_avoidance_module package Takayuki Murooka Yuki Takagi diff --git a/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/plugins.xml b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/plugins.xml new file mode 100644 index 0000000000000..3827012b12e22 --- /dev/null +++ b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/plugins.xml @@ -0,0 +1,3 @@ + + + diff --git a/planning/behavior_path_dynamic_avoidance_module/src/manager.cpp b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/manager.cpp similarity index 97% rename from planning/behavior_path_dynamic_avoidance_module/src/manager.cpp rename to planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/manager.cpp index baa1c631df8da..de524a3b63de9 100644 --- a/planning/behavior_path_dynamic_avoidance_module/src/manager.cpp +++ b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/manager.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_dynamic_avoidance_module/manager.hpp" +#include "autoware_behavior_path_dynamic_obstacle_avoidance_module/manager.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" @@ -37,7 +37,7 @@ PolygonGenerationMethod convertToPolygonGenerationMethod(const std::string & str } } // namespace -void DynamicAvoidanceModuleManager::init(rclcpp::Node * node) +void DynamicObstacleAvoidanceModuleManager::init(rclcpp::Node * node) { // init manager interface initInterface(node, {""}); @@ -149,7 +149,7 @@ void DynamicAvoidanceModuleManager::init(rclcpp::Node * node) parameters_ = std::make_shared(p); } -void DynamicAvoidanceModuleManager::updateModuleParams( +void DynamicObstacleAvoidanceModuleManager::updateModuleParams( [[maybe_unused]] const std::vector & parameters) { using tier4_autoware_utils::updateParam; @@ -287,7 +287,7 @@ void DynamicAvoidanceModuleManager::updateModuleParams( }); } -bool DynamicAvoidanceModuleManager::isAlwaysExecutableModule() const +bool DynamicObstacleAvoidanceModuleManager::isAlwaysExecutableModule() const { return true; } @@ -295,5 +295,5 @@ bool DynamicAvoidanceModuleManager::isAlwaysExecutableModule() const #include PLUGINLIB_EXPORT_CLASS( - behavior_path_planner::DynamicAvoidanceModuleManager, + behavior_path_planner::DynamicObstacleAvoidanceModuleManager, behavior_path_planner::SceneModuleManagerInterface) diff --git a/planning/behavior_path_dynamic_avoidance_module/src/scene.cpp b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp similarity index 96% rename from planning/behavior_path_dynamic_avoidance_module/src/scene.cpp rename to planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp index 84871ed756e81..efc56c4d61f5f 100644 --- a/planning/behavior_path_dynamic_avoidance_module/src/scene.cpp +++ b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_dynamic_avoidance_module/scene.hpp" +#include "autoware_behavior_path_dynamic_obstacle_avoidance_module/scene.hpp" #include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner_common/utils/utils.hpp" @@ -301,7 +301,7 @@ std::vector convertToPoints( } } // namespace -DynamicAvoidanceModule::DynamicAvoidanceModule( +DynamicObstacleAvoidanceModule::DynamicObstacleAvoidanceModule( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, @@ -315,7 +315,7 @@ DynamicAvoidanceModule::DynamicAvoidanceModule( { } -bool DynamicAvoidanceModule::isExecutionRequested() const +bool DynamicObstacleAvoidanceModule::isExecutionRequested() const { RCLCPP_DEBUG(getLogger(), "DYNAMIC AVOIDANCE isExecutionRequested."); @@ -339,13 +339,13 @@ bool DynamicAvoidanceModule::isExecutionRequested() const return !target_objects_.empty(); } -bool DynamicAvoidanceModule::isExecutionReady() const +bool DynamicObstacleAvoidanceModule::isExecutionReady() const { RCLCPP_DEBUG(getLogger(), "DYNAMIC AVOIDANCE isExecutionReady."); return true; } -void DynamicAvoidanceModule::updateData() +void DynamicObstacleAvoidanceModule::updateData() { // stop_watch_.tic(std::string(__func__)); @@ -380,12 +380,12 @@ void DynamicAvoidanceModule::updateData() // [ms]"); } -bool DynamicAvoidanceModule::canTransitSuccessState() +bool DynamicObstacleAvoidanceModule::canTransitSuccessState() { return target_objects_.empty(); } -BehaviorModuleOutput DynamicAvoidanceModule::plan() +BehaviorModuleOutput DynamicObstacleAvoidanceModule::plan() { // stop_watch_.tic(std::string(__func__)); @@ -444,19 +444,19 @@ BehaviorModuleOutput DynamicAvoidanceModule::plan() return output; } -CandidateOutput DynamicAvoidanceModule::planCandidate() const +CandidateOutput DynamicObstacleAvoidanceModule::planCandidate() const { auto candidate_path = utils::generateCenterLinePath(planner_data_); return CandidateOutput(*candidate_path); } -BehaviorModuleOutput DynamicAvoidanceModule::planWaitingApproval() +BehaviorModuleOutput DynamicObstacleAvoidanceModule::planWaitingApproval() { BehaviorModuleOutput out = plan(); return out; } -ObjectType DynamicAvoidanceModule::getObjectType(const uint8_t label) const +ObjectType DynamicObstacleAvoidanceModule::getObjectType(const uint8_t label) const { using autoware_auto_perception_msgs::msg::ObjectClassification; @@ -487,7 +487,7 @@ ObjectType DynamicAvoidanceModule::getObjectType(const uint8_t label) const return ObjectType::OUT_OF_SCOPE; } -void DynamicAvoidanceModule::registerRegulatedObjects( +void DynamicObstacleAvoidanceModule::registerRegulatedObjects( const std::vector & prev_objects) { const auto input_path = getPreviousModuleOutput().path; @@ -575,7 +575,7 @@ void DynamicAvoidanceModule::registerRegulatedObjects( } } -void DynamicAvoidanceModule::registerUnregulatedObjects( +void DynamicObstacleAvoidanceModule::registerUnregulatedObjects( const std::vector & prev_objects) { const auto input_path = getPreviousModuleOutput().path; @@ -649,7 +649,7 @@ void DynamicAvoidanceModule::registerUnregulatedObjects( } } -void DynamicAvoidanceModule::determineWhetherToAvoidAgainstRegulatedObjects( +void DynamicObstacleAvoidanceModule::determineWhetherToAvoidAgainstRegulatedObjects( const std::vector & prev_objects) { const auto & input_path = getPreviousModuleOutput().path; @@ -809,7 +809,7 @@ void DynamicAvoidanceModule::determineWhetherToAvoidAgainstRegulatedObjects( // prev_input_ref_path_points_ = input_ref_path_points; } -void DynamicAvoidanceModule::determineWhetherToAvoidAgainstUnregulatedObjects( +void DynamicObstacleAvoidanceModule::determineWhetherToAvoidAgainstUnregulatedObjects( const std::vector & prev_objects) { const auto & input_path = getPreviousModuleOutput().path; @@ -870,7 +870,7 @@ void DynamicAvoidanceModule::determineWhetherToAvoidAgainstUnregulatedObjects( } } -LatFeasiblePaths DynamicAvoidanceModule::generateLateralFeasiblePaths( +LatFeasiblePaths DynamicObstacleAvoidanceModule::generateLateralFeasiblePaths( const geometry_msgs::msg::Pose & ego_pose, const double ego_vel) const { const double lat_acc = parameters_->max_ego_lat_acc; @@ -907,7 +907,7 @@ LatFeasiblePaths DynamicAvoidanceModule::generateLateralFeasiblePaths( return ego_lat_feasible_paths; } -[[maybe_unused]] void DynamicAvoidanceModule::updateRefPathBeforeLaneChange( +[[maybe_unused]] void DynamicObstacleAvoidanceModule::updateRefPathBeforeLaneChange( const std::vector & ego_ref_path_points) { if (ref_path_before_lane_change_) { @@ -934,7 +934,7 @@ LatFeasiblePaths DynamicAvoidanceModule::generateLateralFeasiblePaths( } [[maybe_unused]] std::optional> -DynamicAvoidanceModule::calcCollisionSection( +DynamicObstacleAvoidanceModule::calcCollisionSection( const std::vector & ego_path, const PredictedPath & obj_path) const { const size_t ego_idx = planner_data_->findEgoIndex(ego_path); @@ -971,7 +971,7 @@ DynamicAvoidanceModule::calcCollisionSection( return std::make_pair(*collision_start_idx, ego_path.size() - 1); } -TimeWhileCollision DynamicAvoidanceModule::calcTimeWhileCollision( +TimeWhileCollision DynamicObstacleAvoidanceModule::calcTimeWhileCollision( const std::vector & ego_path, const double obj_tangent_vel, const LatLonOffset & lat_lon_offset) const { @@ -1027,7 +1027,7 @@ TimeWhileCollision DynamicAvoidanceModule::calcTimeWhileCollision( return TimeWhileCollision{time_to_start_collision, time_to_end_collision}; } -bool DynamicAvoidanceModule::isObjectFarFromPath( +bool DynamicObstacleAvoidanceModule::isObjectFarFromPath( const PredictedObject & predicted_object, const double obj_dist_to_path) const { const double obj_max_length = calcObstacleMaxLength(predicted_object.shape); @@ -1037,7 +1037,7 @@ bool DynamicAvoidanceModule::isObjectFarFromPath( return parameters_->max_obj_lat_offset_to_ego_path < min_obj_dist_to_path; } -bool DynamicAvoidanceModule::willObjectCutIn( +bool DynamicObstacleAvoidanceModule::willObjectCutIn( const std::vector & ego_path, const PredictedPath & predicted_path, const double obj_tangent_vel, const LatLonOffset & lat_lon_offset) const { @@ -1079,7 +1079,7 @@ bool DynamicAvoidanceModule::willObjectCutIn( return true; } -DynamicAvoidanceModule::DecisionWithReason DynamicAvoidanceModule::willObjectCutOut( +DynamicObstacleAvoidanceModule::DecisionWithReason DynamicObstacleAvoidanceModule::willObjectCutOut( const double obj_tangent_vel, const double obj_normal_vel, const bool is_object_left, const std::optional & prev_object) const { @@ -1120,7 +1120,7 @@ DynamicAvoidanceModule::DecisionWithReason DynamicAvoidanceModule::willObjectCut return DecisionWithReason{false}; } -[[maybe_unused]] bool DynamicAvoidanceModule::willObjectBeOutsideEgoChangingPath( +[[maybe_unused]] bool DynamicObstacleAvoidanceModule::willObjectBeOutsideEgoChangingPath( const geometry_msgs::msg::Pose & obj_pose, const autoware_auto_perception_msgs::msg::Shape & obj_shape, const double obj_vel) const { @@ -1139,7 +1139,8 @@ DynamicAvoidanceModule::DecisionWithReason DynamicAvoidanceModule::willObjectCut return true; } -std::pair DynamicAvoidanceModule::getAdjacentLanes( +std::pair +DynamicObstacleAvoidanceModule::getAdjacentLanes( const double forward_distance, const double backward_distance) const { const auto & rh = planner_data_->route_handler; @@ -1179,7 +1180,8 @@ std::pair DynamicAvoidanceModule return std::make_pair(right_lanes, left_lanes); } -DynamicAvoidanceModule::LatLonOffset DynamicAvoidanceModule::getLateralLongitudinalOffset( +DynamicObstacleAvoidanceModule::LatLonOffset +DynamicObstacleAvoidanceModule::getLateralLongitudinalOffset( const std::vector & ego_path, const geometry_msgs::msg::Pose & obj_pose, const autoware_auto_perception_msgs::msg::Shape & obj_shape) const { @@ -1213,7 +1215,7 @@ DynamicAvoidanceModule::LatLonOffset DynamicAvoidanceModule::getLateralLongitudi obj_lon_min_max_offset.max_value, obj_lon_min_max_offset.min_value}; } -MinMaxValue DynamicAvoidanceModule::calcMinMaxLongitudinalOffsetToAvoid( +MinMaxValue DynamicObstacleAvoidanceModule::calcMinMaxLongitudinalOffsetToAvoid( const std::vector & ref_path_points_for_obj_poly, 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, @@ -1286,7 +1288,7 @@ MinMaxValue DynamicAvoidanceModule::calcMinMaxLongitudinalOffsetToAvoid( obj_lon_offset.max_value + end_length_to_avoid}; } -double DynamicAvoidanceModule::calcValidLengthToAvoid( +double DynamicObstacleAvoidanceModule::calcValidLengthToAvoid( const PredictedPath & obj_path, const geometry_msgs::msg::Pose & obj_pose, const autoware_auto_perception_msgs::msg::Shape & obj_shape, const bool is_object_same_direction) const @@ -1379,7 +1381,8 @@ double DynamicAvoidanceModule::calcValidLengthToAvoid( } // min value denotes near side, max value denotes far side -std::optional DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoidRegulatedObject( +std::optional +DynamicObstacleAvoidanceModule::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, @@ -1473,7 +1476,8 @@ std::optional DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoi } // min value denotes near side, max value denotes far side -std::optional DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoidUnregulatedObject( +std::optional +DynamicObstacleAvoidanceModule::calcMinMaxLateralOffsetToAvoidUnregulatedObject( const std::vector & ref_path_points_for_obj_poly, const std::optional & prev_object, const DynamicAvoidanceObject & object) const @@ -1557,7 +1561,7 @@ std::optional DynamicAvoidanceModule::calcMinMaxLateralOffsetToAvoi // NOTE: object does not have const only to update min_bound_lat_offset. std::optional -DynamicAvoidanceModule::calcEgoPathBasedDynamicObstaclePolygon( +DynamicObstacleAvoidanceModule::calcEgoPathBasedDynamicObstaclePolygon( const DynamicAvoidanceObject & object) const { if (!object.lon_offset_to_avoid || !object.lat_offset_to_avoid) { @@ -1663,7 +1667,7 @@ DynamicAvoidanceModule::calcEgoPathBasedDynamicObstaclePolygon( // should be replace by the function calcPredictedPathBasedDynamicObstaclePolygon() (takagi) std::optional -DynamicAvoidanceModule::calcObjectPathBasedDynamicObstaclePolygon( +DynamicObstacleAvoidanceModule::calcObjectPathBasedDynamicObstaclePolygon( const DynamicAvoidanceObject & object) const { const auto obj_path = *std::max_element( @@ -1722,7 +1726,7 @@ DynamicAvoidanceModule::calcObjectPathBasedDynamicObstaclePolygon( // 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( +DynamicObstacleAvoidanceModule::calcPredictedPathBasedDynamicObstaclePolygon( const DynamicAvoidanceObject & object, const EgoPathReservePoly & ego_path_poly) const { std::vector obj_poses; @@ -1783,8 +1787,8 @@ DynamicAvoidanceModule::calcPredictedPathBasedDynamicObstaclePolygon( // 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 +DynamicObstacleAvoidanceModule::EgoPathReservePoly +DynamicObstacleAvoidanceModule::calcEgoPathReservePoly(const PathWithLaneId & ego_path) const { // This function require almost 0.5 ms. Should be refactored in the future // double calculation_time; @@ -1799,11 +1803,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( diff --git a/planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp b/planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp similarity index 92% rename from planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp rename to planning/autoware_behavior_path_dynamic_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp index 8cf85554e2b2c..bd9e6fd483c7c 100644 --- a/planning/behavior_path_avoidance_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/autoware_behavior_path_dynamic_obstacle_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 @@ -47,7 +47,7 @@ std::shared_ptr generateNode() ament_index_cpp::get_package_share_directory("behavior_path_planner"); std::vector module_names; - module_names.emplace_back("behavior_path_planner::AvoidanceModuleManager"); + module_names.emplace_back("behavior_path_planner::DynamicAvoidanceModuleManager"); std::vector params; params.emplace_back("launch_modules", module_names); @@ -60,8 +60,9 @@ std::shared_ptr generateNode() behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", - ament_index_cpp::get_package_share_directory("behavior_path_avoidance_module") + - "/config/avoidance.param.yaml"}); + ament_index_cpp::get_package_share_directory( + "autoware_behavior_path_dynamic_obstacle_avoidance_module") + + "/config/dynamic_obstacle_avoidance.param.yaml"}); return std::make_shared(node_options); } diff --git a/planning/behavior_path_external_request_lane_change_module/CMakeLists.txt b/planning/autoware_behavior_path_external_request_lane_change_module/CMakeLists.txt similarity index 88% rename from planning/behavior_path_external_request_lane_change_module/CMakeLists.txt rename to planning/autoware_behavior_path_external_request_lane_change_module/CMakeLists.txt index 86dc0ccb61330..662d36618e766 100644 --- a/planning/behavior_path_external_request_lane_change_module/CMakeLists.txt +++ b/planning/autoware_behavior_path_external_request_lane_change_module/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(behavior_path_external_request_lane_change_module) +project(autoware_behavior_path_external_request_lane_change_module) find_package(autoware_cmake REQUIRED) autoware_package() diff --git a/planning/behavior_path_external_request_lane_change_module/package.xml b/planning/autoware_behavior_path_external_request_lane_change_module/package.xml similarity index 89% rename from planning/behavior_path_external_request_lane_change_module/package.xml rename to planning/autoware_behavior_path_external_request_lane_change_module/package.xml index 16216aa1f71e9..c08eb20a2b589 100644 --- a/planning/behavior_path_external_request_lane_change_module/package.xml +++ b/planning/autoware_behavior_path_external_request_lane_change_module/package.xml @@ -1,9 +1,9 @@ - behavior_path_external_request_lane_change_module + autoware_behavior_path_external_request_lane_change_module 0.1.0 - The behavior_path_external_request_lane_change_module package + The autoware_behavior_path_external_request_lane_change_module package Fumiya Watanabe Zulfaqar Azmi diff --git a/planning/autoware_behavior_path_external_request_lane_change_module/plugins.xml b/planning/autoware_behavior_path_external_request_lane_change_module/plugins.xml new file mode 100644 index 0000000000000..d13dff53e0836 --- /dev/null +++ b/planning/autoware_behavior_path_external_request_lane_change_module/plugins.xml @@ -0,0 +1,4 @@ + + + + diff --git a/planning/behavior_path_external_request_lane_change_module/src/manager.cpp b/planning/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp similarity index 75% rename from planning/behavior_path_external_request_lane_change_module/src/manager.cpp rename to planning/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp index 3cfe7aa51f0f1..130cbff29bcf3 100644 --- a/planning/behavior_path_external_request_lane_change_module/src/manager.cpp +++ b/planning/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp @@ -12,13 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_external_request_lane_change_module/manager.hpp" +#include "manager.hpp" -#include "behavior_path_external_request_lane_change_module/scene.hpp" #include "behavior_path_lane_change_module/interface.hpp" +#include "scene.hpp" -namespace behavior_path_planner +namespace autoware::behavior_path_planner { +using ::behavior_path_planner::LaneChangeInterface; std::unique_ptr ExternalRequestLaneChangeRightModuleManager::createNewSceneModuleInstance() @@ -38,12 +39,12 @@ ExternalRequestLaneChangeLeftModuleManager::createNewSceneModuleInstance() std::make_unique(parameters_, direction_)); } -} // namespace behavior_path_planner +} // namespace autoware::behavior_path_planner #include PLUGINLIB_EXPORT_CLASS( - behavior_path_planner::ExternalRequestLaneChangeRightModuleManager, - behavior_path_planner::SceneModuleManagerInterface) + autoware::behavior_path_planner::ExternalRequestLaneChangeRightModuleManager, + ::behavior_path_planner::SceneModuleManagerInterface) PLUGINLIB_EXPORT_CLASS( - behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager, - behavior_path_planner::SceneModuleManagerInterface) + autoware::behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager, + ::behavior_path_planner::SceneModuleManagerInterface) diff --git a/planning/behavior_path_external_request_lane_change_module/include/behavior_path_external_request_lane_change_module/manager.hpp b/planning/autoware_behavior_path_external_request_lane_change_module/src/manager.hpp similarity index 82% rename from planning/behavior_path_external_request_lane_change_module/include/behavior_path_external_request_lane_change_module/manager.hpp rename to planning/autoware_behavior_path_external_request_lane_change_module/src/manager.hpp index dfcc4f61d8241..a4f3dce188c73 100644 --- a/planning/behavior_path_external_request_lane_change_module/include/behavior_path_external_request_lane_change_module/manager.hpp +++ b/planning/autoware_behavior_path_external_request_lane_change_module/src/manager.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_EXTERNAL_REQUEST_LANE_CHANGE_MODULE__MANAGER_HPP_ -#define BEHAVIOR_PATH_EXTERNAL_REQUEST_LANE_CHANGE_MODULE__MANAGER_HPP_ +#ifndef MANAGER_HPP_ +#define MANAGER_HPP_ #include "behavior_path_lane_change_module/manager.hpp" #include "route_handler/route_handler.hpp" @@ -23,8 +23,12 @@ #include #include -namespace behavior_path_planner +namespace autoware::behavior_path_planner { +using ::behavior_path_planner::LaneChangeModuleManager; +using ::behavior_path_planner::LaneChangeModuleType; +using ::behavior_path_planner::SceneModuleInterface; + class ExternalRequestLaneChangeRightModuleManager : public LaneChangeModuleManager { public: @@ -49,6 +53,6 @@ class ExternalRequestLaneChangeLeftModuleManager : public LaneChangeModuleManage } std::unique_ptr createNewSceneModuleInstance() override; }; -} // namespace behavior_path_planner +} // namespace autoware::behavior_path_planner -#endif // BEHAVIOR_PATH_EXTERNAL_REQUEST_LANE_CHANGE_MODULE__MANAGER_HPP_ +#endif // MANAGER_HPP_ diff --git a/planning/behavior_path_external_request_lane_change_module/src/scene.cpp b/planning/autoware_behavior_path_external_request_lane_change_module/src/scene.cpp similarity index 84% rename from planning/behavior_path_external_request_lane_change_module/src/scene.cpp rename to planning/autoware_behavior_path_external_request_lane_change_module/src/scene.cpp index 913266bf79fa3..2ba5a5aea34d4 100644 --- a/planning/behavior_path_external_request_lane_change_module/src/scene.cpp +++ b/planning/autoware_behavior_path_external_request_lane_change_module/src/scene.cpp @@ -12,17 +12,19 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_external_request_lane_change_module/scene.hpp" +#include "scene.hpp" #include #include -namespace behavior_path_planner +namespace autoware::behavior_path_planner { +using ::behavior_path_planner::LaneChangeModuleType; + ExternalRequestLaneChange::ExternalRequestLaneChange( const std::shared_ptr & parameters, Direction direction) : NormalLaneChange(parameters, LaneChangeModuleType::EXTERNAL_REQUEST, direction) { } -} // namespace behavior_path_planner +} // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_external_request_lane_change_module/include/behavior_path_external_request_lane_change_module/scene.hpp b/planning/autoware_behavior_path_external_request_lane_change_module/src/scene.hpp similarity index 80% rename from planning/behavior_path_external_request_lane_change_module/include/behavior_path_external_request_lane_change_module/scene.hpp rename to planning/autoware_behavior_path_external_request_lane_change_module/src/scene.hpp index c23d6f2f3996c..d2eb20b048a5d 100644 --- a/planning/behavior_path_external_request_lane_change_module/include/behavior_path_external_request_lane_change_module/scene.hpp +++ b/planning/autoware_behavior_path_external_request_lane_change_module/src/scene.hpp @@ -12,15 +12,19 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_EXTERNAL_REQUEST_LANE_CHANGE_MODULE__SCENE_HPP_ -#define BEHAVIOR_PATH_EXTERNAL_REQUEST_LANE_CHANGE_MODULE__SCENE_HPP_ +#ifndef SCENE_HPP_ +#define SCENE_HPP_ #include "behavior_path_lane_change_module/scene.hpp" #include -namespace behavior_path_planner +namespace autoware::behavior_path_planner { +using ::behavior_path_planner::Direction; +using ::behavior_path_planner::LaneChangeParameters; +using ::behavior_path_planner::NormalLaneChange; + class ExternalRequestLaneChange : public NormalLaneChange { public: @@ -33,6 +37,6 @@ class ExternalRequestLaneChange : public NormalLaneChange ExternalRequestLaneChange & operator=(ExternalRequestLaneChange &&) = delete; ~ExternalRequestLaneChange() override = default; }; -} // namespace behavior_path_planner +} // namespace autoware::behavior_path_planner -#endif // BEHAVIOR_PATH_EXTERNAL_REQUEST_LANE_CHANGE_MODULE__SCENE_HPP_ +#endif // SCENE_HPP_ diff --git a/planning/behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/autoware_behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp similarity index 92% rename from planning/behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp rename to planning/autoware_behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp index 434988cc3ab08..201d01e9b7fa0 100644 --- a/planning/behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/autoware_behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -13,16 +13,16 @@ // 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 #include #include -using behavior_path_planner::BehaviorPathPlannerNode; +using ::behavior_path_planner::BehaviorPathPlannerNode; using planning_test_utils::PlanningInterfaceTestManager; std::shared_ptr generateTestManager() @@ -51,8 +51,10 @@ std::shared_ptr generateNode() ament_index_cpp::get_package_share_directory("behavior_path_lane_change_module"); std::vector module_names; - module_names.emplace_back("behavior_path_planner::ExternalRequestLaneChangeRightModuleManager"); - module_names.emplace_back("behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager"); + module_names.emplace_back( + "autoware::behavior_path_planner::ExternalRequestLaneChangeRightModuleManager"); + module_names.emplace_back( + "autoware::behavior_path_planner::ExternalRequestLaneChangeLeftModuleManager"); std::vector params; params.emplace_back("launch_modules", module_names); diff --git a/planning/behavior_path_avoidance_module/CMakeLists.txt b/planning/autoware_behavior_path_static_obstacle_avoidance_module/CMakeLists.txt similarity index 91% rename from planning/behavior_path_avoidance_module/CMakeLists.txt rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/CMakeLists.txt index c94591f9bbd30..e646ad29ed42a 100644 --- a/planning/behavior_path_avoidance_module/CMakeLists.txt +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(behavior_path_avoidance_module) +project(autoware_behavior_path_static_obstacle_avoidance_module) find_package(autoware_cmake REQUIRED) autoware_package() diff --git a/planning/behavior_path_avoidance_module/README.md b/planning/autoware_behavior_path_static_obstacle_avoidance_module/README.md similarity index 98% rename from planning/behavior_path_avoidance_module/README.md rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/README.md index aa7a3a42efdb4..93b57ac3a4831 100644 --- a/planning/behavior_path_avoidance_module/README.md +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/README.md @@ -758,9 +758,9 @@ WIP ## Parameters -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`. +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/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml`. -{{ json_to_markdown("planning/behavior_path_avoidance_module/schema/avoidance.schema.json") }} +{{ json_to_markdown("planning/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json") }} ## Future extensions / Unimplemented parts @@ -797,7 +797,7 @@ Developers can see what is going on in each process by visualizing all the avoid ![fig1](./images/avoidance-debug-marker.png) -To enable the debug marker, execute `ros2 param set /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner avoidance.publish_debug_marker true` (no restart is needed) or simply set the `publish_debug_marker` to `true` in the `avoidance.param.yaml` for permanent effect (restart is needed). Then add the marker `/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/avoidance` in `rviz2`. +To enable the debug marker, execute `ros2 param set /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner avoidance.publish_debug_marker true` (no restart is needed) or simply set the `publish_debug_marker` to `true` in the `static_obstacle_avoidance.param.yaml` for permanent effect (restart is needed). Then add the marker `/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/avoidance` in `rviz2`. ### Echoing debug message to find out why the objects were ignored diff --git a/planning/behavior_path_avoidance_module/config/avoidance.param.yaml b/planning/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml similarity index 96% rename from planning/behavior_path_avoidance_module/config/avoidance.param.yaml rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml index c85fdd5a2351a..884812d0db716 100644 --- a/planning/behavior_path_avoidance_module/config/avoidance.param.yaml +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/config/static_obstacle_avoidance.param.yaml @@ -132,6 +132,10 @@ th_shiftable_ratio: 0.8 # [-] min_road_shoulder_width: 0.5 # [m] FOR DEVELOPER + # for merging/deviating vehicle + merging_vehicle: + th_overhang_distance: 0.0 # [m] + # params for avoidance of vehicle type objects that are ambiguous as to whether they are parked. avoidance_for_ambiguous_vehicle: enable: true # [-] @@ -289,4 +293,11 @@ # for debug debug: - marker: false + enable_other_objects_marker: false + enable_other_objects_info: false + enable_detection_area_marker: false + enable_drivable_bound_marker: false + enable_safety_check_marker: false + enable_shift_line_marker: false + enable_lane_marker: false + enable_misc_marker: false diff --git a/planning/behavior_path_avoidance_module/images/avoidance-debug-marker.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/avoidance-debug-marker.png similarity index 100% rename from planning/behavior_path_avoidance_module/images/avoidance-debug-marker.png rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/avoidance-debug-marker.png diff --git a/planning/behavior_path_avoidance_module/images/avoidance_debug_message_array.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/avoidance_debug_message_array.png similarity index 100% rename from planning/behavior_path_avoidance_module/images/avoidance_debug_message_array.png rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/avoidance_debug_message_array.png diff --git a/planning/behavior_path_avoidance_module/images/avoidance_design.fig1.drawio.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/avoidance_design.fig1.drawio.svg similarity index 100% rename from planning/behavior_path_avoidance_module/images/avoidance_design.fig1.drawio.svg rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/avoidance_design.fig1.drawio.svg diff --git a/planning/behavior_path_avoidance_module/images/avoidance_module-shift_point_and_its_constraints.drawio.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/avoidance_module-shift_point_and_its_constraints.drawio.png similarity index 100% rename from planning/behavior_path_avoidance_module/images/avoidance_module-shift_point_and_its_constraints.drawio.png rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/avoidance_module-shift_point_and_its_constraints.drawio.png diff --git a/planning/behavior_path_avoidance_module/images/dynamic_lateral_margin.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/dynamic_lateral_margin.svg similarity index 100% rename from planning/behavior_path_avoidance_module/images/dynamic_lateral_margin.svg rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/dynamic_lateral_margin.svg diff --git a/planning/behavior_path_avoidance_module/images/envelope_polygon.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/envelope_polygon.svg similarity index 100% rename from planning/behavior_path_avoidance_module/images/envelope_polygon.svg rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/envelope_polygon.svg diff --git a/planning/behavior_path_avoidance_module/images/how_to_decide_path_shape_multi_object_both_direction.drawio.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/how_to_decide_path_shape_multi_object_both_direction.drawio.svg similarity index 100% rename from planning/behavior_path_avoidance_module/images/how_to_decide_path_shape_multi_object_both_direction.drawio.svg rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/how_to_decide_path_shape_multi_object_both_direction.drawio.svg diff --git a/planning/behavior_path_avoidance_module/images/how_to_decide_path_shape_multi_object_one_direction.drawio.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/how_to_decide_path_shape_multi_object_one_direction.drawio.svg similarity index 100% rename from planning/behavior_path_avoidance_module/images/how_to_decide_path_shape_multi_object_one_direction.drawio.svg rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/how_to_decide_path_shape_multi_object_one_direction.drawio.svg diff --git a/planning/behavior_path_avoidance_module/images/how_to_decide_path_shape_one_object.drawio.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/how_to_decide_path_shape_one_object.drawio.svg similarity index 100% rename from planning/behavior_path_avoidance_module/images/how_to_decide_path_shape_one_object.drawio.svg rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/how_to_decide_path_shape_one_object.drawio.svg diff --git a/planning/behavior_path_avoidance_module/images/intersection_problem.drawio.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/intersection_problem.drawio.svg similarity index 100% rename from planning/behavior_path_avoidance_module/images/intersection_problem.drawio.svg rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/intersection_problem.drawio.svg diff --git a/planning/behavior_path_avoidance_module/images/obstacle_to_road_shoulder_distance.drawio.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/obstacle_to_road_shoulder_distance.drawio.svg similarity index 100% rename from planning/behavior_path_avoidance_module/images/obstacle_to_road_shoulder_distance.drawio.svg rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/obstacle_to_road_shoulder_distance.drawio.svg diff --git a/planning/behavior_path_avoidance_module/images/parked-car-detection.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/parked-car-detection.svg similarity index 100% rename from planning/behavior_path_avoidance_module/images/parked-car-detection.svg rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/parked-car-detection.svg diff --git a/planning/behavior_path_avoidance_module/images/safety_check_flowchart.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/safety_check_flowchart.svg similarity index 100% rename from planning/behavior_path_avoidance_module/images/safety_check_flowchart.svg rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/safety_check_flowchart.svg diff --git a/planning/behavior_path_avoidance_module/images/safety_check_margin.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/safety_check_margin.svg similarity index 100% rename from planning/behavior_path_avoidance_module/images/safety_check_margin.svg rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/safety_check_margin.svg diff --git a/planning/behavior_path_avoidance_module/images/safety_check_step_1.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/safety_check_step_1.svg similarity index 100% rename from planning/behavior_path_avoidance_module/images/safety_check_step_1.svg rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/safety_check_step_1.svg diff --git a/planning/behavior_path_avoidance_module/images/safety_check_step_2.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/safety_check_step_2.svg similarity index 100% rename from planning/behavior_path_avoidance_module/images/safety_check_step_2.svg rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/safety_check_step_2.svg diff --git a/planning/behavior_path_avoidance_module/images/shift_length_parameters.drawio.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/shift_length_parameters.drawio.svg similarity index 100% rename from planning/behavior_path_avoidance_module/images/shift_length_parameters.drawio.svg rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/shift_length_parameters.drawio.svg diff --git a/planning/behavior_path_avoidance_module/images/shift_line_generation.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/shift_line_generation.svg similarity index 100% rename from planning/behavior_path_avoidance_module/images/shift_line_generation.svg rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/shift_line_generation.svg diff --git a/planning/behavior_path_avoidance_module/images/target_vehicle_selection.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_vehicle_selection.svg similarity index 100% rename from planning/behavior_path_avoidance_module/images/target_vehicle_selection.svg rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/target_vehicle_selection.svg diff --git a/planning/behavior_path_avoidance_module/images/todo.png b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/todo.png similarity index 100% rename from planning/behavior_path_avoidance_module/images/todo.png rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/todo.png diff --git a/planning/behavior_path_avoidance_module/images/use_adjacent_lane.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/use_adjacent_lane.svg similarity index 100% rename from planning/behavior_path_avoidance_module/images/use_adjacent_lane.svg rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/use_adjacent_lane.svg diff --git a/planning/behavior_path_avoidance_module/images/use_hatched_road_markings.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/use_hatched_road_markings.svg similarity index 100% rename from planning/behavior_path_avoidance_module/images/use_hatched_road_markings.svg rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/use_hatched_road_markings.svg diff --git a/planning/behavior_path_avoidance_module/images/use_intersection_areas.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/use_intersection_areas.svg similarity index 100% rename from planning/behavior_path_avoidance_module/images/use_intersection_areas.svg rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/use_intersection_areas.svg diff --git a/planning/behavior_path_avoidance_module/images/use_opposite_lane.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/use_opposite_lane.svg similarity index 100% rename from planning/behavior_path_avoidance_module/images/use_opposite_lane.svg rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/use_opposite_lane.svg diff --git a/planning/behavior_path_avoidance_module/images/yield_limitation.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/yield_limitation.svg similarity index 100% rename from planning/behavior_path_avoidance_module/images/yield_limitation.svg rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/yield_limitation.svg diff --git a/planning/behavior_path_avoidance_module/images/yield_maneuver.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/yield_maneuver.svg similarity index 100% rename from planning/behavior_path_avoidance_module/images/yield_maneuver.svg rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/yield_maneuver.svg diff --git a/planning/behavior_path_avoidance_module/images/yield_maneuver_flowchart.svg b/planning/autoware_behavior_path_static_obstacle_avoidance_module/images/yield_maneuver_flowchart.svg similarity index 100% rename from planning/behavior_path_avoidance_module/images/yield_maneuver_flowchart.svg rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/images/yield_maneuver_flowchart.svg diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp b/planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/data_structs.hpp similarity index 92% rename from planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/data_structs.hpp index 8516cc61f860b..a63c283704001 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/data_structs.hpp @@ -12,19 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_AVOIDANCE_MODULE__DATA_STRUCTS_HPP_ -#define BEHAVIOR_PATH_AVOIDANCE_MODULE__DATA_STRUCTS_HPP_ +#ifndef AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__DATA_STRUCTS_HPP_ +#define AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__DATA_STRUCTS_HPP_ +#include "autoware_behavior_path_static_obstacle_avoidance_module/type_alias.hpp" #include "behavior_path_planner_common/data_manager.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" #include -#include - -#include -#include -#include #include #include @@ -38,21 +34,38 @@ namespace behavior_path_planner { -using autoware_auto_perception_msgs::msg::PredictedObject; -using autoware_auto_perception_msgs::msg::PredictedPath; -using autoware_auto_planning_msgs::msg::PathWithLaneId; - -using tier4_autoware_utils::Point2d; -using tier4_autoware_utils::Polygon2d; -using tier4_planning_msgs::msg::AvoidanceDebugMsgArray; - -using geometry_msgs::msg::Point; -using geometry_msgs::msg::Pose; using behavior_path_planner::utils::path_safety_checker::CollisionCheckDebug; - using route_handler::Direction; +enum class ObjectInfo { + NONE = 0, + // ignore reasons + OUT_OF_TARGET_AREA, + FURTHER_THAN_THRESHOLD, + FURTHER_THAN_GOAL, + IS_NOT_TARGET_OBJECT, + IS_NOT_PARKING_OBJECT, + TOO_NEAR_TO_CENTERLINE, + TOO_NEAR_TO_GOAL, + MOVING_OBJECT, + UNSTABLE_OBJECT, + CROSSWALK_USER, + ENOUGH_LATERAL_DISTANCE, + LESS_THAN_EXECUTION_THRESHOLD, + PARALLEL_TO_EGO_LANE, + MERGING_TO_EGO_LANE, + DEVIATING_FROM_EGO_LANE, + // unavoidable reasons + NEED_DECELERATION, + SAME_DIRECTION_SHIFT, + INSUFFICIENT_DRIVABLE_SPACE, + INSUFFICIENT_LONGITUDINAL_DISTANCE, + INVALID_SHIFT_LINE, + // others + AMBIGUOUS_STOPPED_VEHICLE, +}; + struct ObjectParameter { bool is_avoidance_target{false}; @@ -189,6 +202,9 @@ struct AvoidanceParameters double time_threshold_for_ambiguous_vehicle{0.0}; double distance_threshold_for_ambiguous_vehicle{0.0}; + // for merging/deviating vehicle + double th_overhang_distance{0.0}; + // parameters for safety check area bool enable_safety_check{false}; bool check_current_lane{false}; @@ -321,7 +337,14 @@ struct AvoidanceParameters bool enable_bound_clipping{false}; // debug - bool publish_debug_marker = false; + bool enable_other_objects_marker{false}; + bool enable_other_objects_info{false}; + bool enable_detection_area_marker{false}; + bool enable_drivable_bound_marker{false}; + bool enable_safety_check_marker{false}; + bool enable_shift_line_marker{false}; + bool enable_lane_marker{false}; + bool enable_misc_marker{false}; }; struct ObjectData // avoidance target @@ -420,8 +443,8 @@ struct ObjectData // avoidance target // overhang points (sort by distance) std::vector> overhang_points{}; - // unavoidable reason - std::string reason{}; + // object detail info + ObjectInfo info{ObjectInfo::NONE}; // lateral avoid margin std::optional avoid_margin{std::nullopt}; @@ -478,11 +501,9 @@ using AvoidOutlines = std::vector; * avoidance state */ enum class AvoidanceState { - NOT_AVOID = 0, - AVOID_EXECUTE, - YIELD, - AVOID_PATH_READY, - AVOID_PATH_NOT_READY, + RUNNING = 0, + CANCEL, + SUCCEEDED, }; /* @@ -491,7 +512,7 @@ enum class AvoidanceState { struct AvoidancePlanningData { // ego final state - AvoidanceState state{AvoidanceState::NOT_AVOID}; + AvoidanceState state{AvoidanceState::RUNNING}; // un-shifted pose (for current lane detection) Pose reference_pose; @@ -543,8 +564,6 @@ struct AvoidancePlanningData bool ready{false}; - bool success{false}; - bool comfortable{false}; bool avoid_required{false}; @@ -651,4 +670,4 @@ struct DebugData } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__DATA_STRUCTS_HPP_ +#endif // AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__DATA_STRUCTS_HPP_ diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/debug.hpp b/planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/debug.hpp similarity index 67% rename from planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/debug.hpp rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/debug.hpp index f49f457ddd066..85b0e1aad0ae3 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/debug.hpp +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/debug.hpp @@ -12,29 +12,26 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_AVOIDANCE_MODULE__DEBUG_HPP_ -#define BEHAVIOR_PATH_AVOIDANCE_MODULE__DEBUG_HPP_ +#ifndef AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__DEBUG_HPP_ +#define AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__DEBUG_HPP_ -#include "behavior_path_avoidance_module/data_structs.hpp" - -#include - -#include -#include +#include "autoware_behavior_path_static_obstacle_avoidance_module/data_structs.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/type_alias.hpp" +#include #include -namespace marker_utils::avoidance_marker +namespace behavior_path_planner::utils::static_obstacle_avoidance { -using autoware_auto_planning_msgs::msg::PathWithLaneId; + +using behavior_path_planner::AvoidanceParameters; using behavior_path_planner::AvoidancePlanningData; using behavior_path_planner::AvoidLineArray; using behavior_path_planner::DebugData; using behavior_path_planner::ObjectDataArray; +using behavior_path_planner::ObjectInfo; using behavior_path_planner::PathShifter; using behavior_path_planner::ShiftLineArray; -using geometry_msgs::msg::Pose; -using visualization_msgs::msg::MarkerArray; MarkerArray createEgoStatusMarkerArray( const AvoidancePlanningData & data, const Pose & p_ego, std::string && ns); @@ -47,11 +44,13 @@ MarkerArray createPredictedVehiclePositions(const PathWithLaneId & path, std::st MarkerArray createTargetObjectsMarkerArray(const ObjectDataArray & objects, const std::string & ns); -MarkerArray createOtherObjectsMarkerArray(const ObjectDataArray & objects, const std::string & ns); +MarkerArray createOtherObjectsMarkerArray( + const ObjectDataArray & objects, const ObjectInfo & info, const bool verbose); MarkerArray createDebugMarkerArray( - const AvoidancePlanningData & data, const PathShifter & shifter, const DebugData & debug); -} // namespace marker_utils::avoidance_marker + const AvoidancePlanningData & data, const PathShifter & shifter, const DebugData & debug, + const std::shared_ptr & parameters); +} // namespace behavior_path_planner::utils::static_obstacle_avoidance std::string toStrInfo(const behavior_path_planner::ShiftLineArray & sl_arr); @@ -61,4 +60,4 @@ std::string toStrInfo(const behavior_path_planner::ShiftLine & sl); std::string toStrInfo(const behavior_path_planner::AvoidLine & ap); -#endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__DEBUG_HPP_ +#endif // AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__DEBUG_HPP_ diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp b/planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/helper.hpp similarity index 86% rename from planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/helper.hpp index 8d95e724045ba..5da56a320ad3b 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/helper.hpp +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/helper.hpp @@ -12,31 +12,25 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_AVOIDANCE_MODULE__HELPER_HPP_ -#define BEHAVIOR_PATH_AVOIDANCE_MODULE__HELPER_HPP_ +#ifndef AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__HELPER_HPP_ +#define AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__HELPER_HPP_ -#include "behavior_path_avoidance_module/data_structs.hpp" -#include "behavior_path_avoidance_module/utils.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/data_structs.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/type_alias.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/utils.hpp" #include "behavior_path_planner_common/utils/utils.hpp" -#include - #include #include #include #include #include -namespace behavior_path_planner::helper::avoidance +namespace behavior_path_planner::helper::static_obstacle_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 { @@ -103,16 +97,18 @@ class AvoidanceHelper return std::max(getEgoSpeed(), values.at(idx)); } - double getMinimumPrepareDistance() const + double getNominalPrepareDistance(const double velocity) const { const auto & p = parameters_; - return std::max(getEgoSpeed() * p->min_prepare_time, p->min_prepare_distance); + const auto & values = p->velocity_map; + const auto idx = getConstraintsMapIndex(velocity, values); + return std::max(values.at(idx) * p->max_prepare_time, p->min_prepare_distance); } double getNominalPrepareDistance() const { const auto & p = parameters_; - return std::max(getEgoSpeed() * p->max_prepare_time, p->min_prepare_distance); + return std::max(getAvoidanceEgoSpeed() * p->max_prepare_time, p->min_prepare_distance); } double getNominalAvoidanceDistance(const double shift_length) const @@ -181,14 +177,14 @@ class AvoidanceHelper double getShift(const Point & p) const { validate(); - const auto idx = findNearestIndex(prev_reference_path_.points, p); + const auto idx = motion_utils::findNearestIndex(prev_reference_path_.points, p); return prev_spline_shift_path_.shift_length.at(idx); } double getLinearShift(const Point & p) const { validate(); - const auto idx = findNearestIndex(prev_reference_path_.points, p); + const auto idx = motion_utils::findNearestIndex(prev_reference_path_.points, p); return prev_linear_shift_path_.shift_length.at(idx); } @@ -204,7 +200,7 @@ class AvoidanceHelper double getShiftLength( const ObjectData & object, const bool & is_on_right, const double & margin) const { - using utils::avoidance::calcShiftLength; + using utils::static_obstacle_avoidance::calcShiftLength; const auto shift_length = calcShiftLength(is_on_right, object.overhang_points.front().first, margin); @@ -282,8 +278,8 @@ class AvoidanceHelper } const auto start_idx = data_->findEgoIndex(path.points); - const auto distance = - calcSignedArcLength(path.points, start_idx, max_v_point_.value().first.position); + const auto distance = motion_utils::calcSignedArcLength( + path.points, start_idx, max_v_point_.value().first.position); return std::make_pair(distance, max_v_point_.value().second); } @@ -294,7 +290,7 @@ class AvoidanceHelper const auto & a_now = data_->self_acceleration->accel.accel.linear.x; const auto & a_lim = use_hard_constraints ? p->max_deceleration : p->nominal_deceleration; const auto & j_lim = use_hard_constraints ? p->max_jerk : p->nominal_jerk; - const auto ret = calcDecelDistWithJerkAndAccConstraints( + const auto ret = motion_utils::calcDecelDistWithJerkAndAccConstraints( getEgoSpeed(), target_velocity, a_now, a_lim, j_lim, -1.0 * j_lim); if (!!ret) { @@ -304,6 +300,13 @@ class AvoidanceHelper return std::numeric_limits::max(); } + bool isEnoughPrepareDistance(const double prepare_distance) const + { + const auto & p = parameters_; + return prepare_distance > + std::max(getEgoSpeed() * p->min_prepare_distance, p->min_prepare_distance); + } + bool isComfortable(const AvoidLineArray & shift_lines) const { const auto JERK_BUFFER = 0.1; // [m/sss] @@ -330,11 +333,11 @@ class AvoidanceHelper return true; } - const auto is_object_on_right = utils::avoidance::isOnRight(object); + const auto is_object_on_right = utils::static_obstacle_avoidance::isOnRight(object); const auto desire_shift_length = getShiftLength(object, is_object_on_right, object.avoid_margin.value()); - const auto prepare_distance = getMinimumPrepareDistance(); + const auto prepare_distance = getNominalPrepareDistance(0.0); const auto constant_distance = getFrontConstantDistance(object); const auto avoidance_distance = getMinAvoidanceDistance(desire_shift_length); @@ -343,6 +346,20 @@ class AvoidanceHelper parameters_->closest_distance_to_wait_and_see_for_ambiguous_vehicle; } + static bool isAbsolutelyNotAvoidable(const ObjectData & object) + { + if (object.is_avoidable) { + return false; + } + + // can avoid it after deceleration. + if (object.info == ObjectInfo::NEED_DECELERATION) { + return false; + } + + return true; + } + bool isReady(const AvoidLineArray & new_shift_lines, const double current_shift_length) const { if (std::abs(current_shift_length) < 1e-3) { @@ -427,14 +444,15 @@ class AvoidanceHelper 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); + const auto point = motion_utils::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 x_end = + motion_utils::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; @@ -495,6 +513,6 @@ class AvoidanceHelper std::optional> max_v_point_; }; -} // namespace behavior_path_planner::helper::avoidance +} // namespace behavior_path_planner::helper::static_obstacle_avoidance -#endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__HELPER_HPP_ +#endif // AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__HELPER_HPP_ diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/manager.hpp b/planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/manager.hpp similarity index 66% rename from planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/manager.hpp rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/manager.hpp index e23a8a96ee7da..1616339840ba4 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/manager.hpp +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/manager.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_AVOIDANCE_MODULE__MANAGER_HPP_ -#define BEHAVIOR_PATH_AVOIDANCE_MODULE__MANAGER_HPP_ +#ifndef AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__MANAGER_HPP_ +#define AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__MANAGER_HPP_ -#include "behavior_path_avoidance_module/data_structs.hpp" -#include "behavior_path_avoidance_module/scene.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/data_structs.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/scene.hpp" #include "behavior_path_planner_common/interface/scene_module_manager_interface.hpp" #include @@ -28,16 +28,18 @@ namespace behavior_path_planner { -class AvoidanceModuleManager : public SceneModuleManagerInterface +class StaticObstacleAvoidanceModuleManager : public SceneModuleManagerInterface { public: - AvoidanceModuleManager() : SceneModuleManagerInterface{"avoidance"} {} + StaticObstacleAvoidanceModuleManager() : SceneModuleManagerInterface{"static_obstacle_avoidance"} + { + } void init(rclcpp::Node * node) override; std::unique_ptr createNewSceneModuleInstance() override { - return std::make_unique( + return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, objects_of_interest_marker_interface_ptr_map_); } @@ -50,4 +52,4 @@ class AvoidanceModuleManager : public SceneModuleManagerInterface } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__MANAGER_HPP_ +#endif // AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__MANAGER_HPP_ diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp b/planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp similarity index 93% rename from planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp index e115e676b1dbf..56b9bad535e7d 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/parameter_helper.hpp +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp @@ -11,12 +11,12 @@ // 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 BEHAVIOR_PATH_AVOIDANCE_MODULE__PARAMETER_HELPER_HPP_ -#define BEHAVIOR_PATH_AVOIDANCE_MODULE__PARAMETER_HELPER_HPP_ +#ifndef AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__PARAMETER_HELPER_HPP_ +#define AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__PARAMETER_HELPER_HPP_ #include "tier4_autoware_utils/ros/parameter.hpp" -#include +#include #include #include @@ -131,6 +131,11 @@ AvoidanceParameters getParameter(rclcpp::Node * node) getOrDeclareParameter(*node, ns + "min_road_shoulder_width"); } + { + const std::string ns = "avoidance.target_filtering.merging_vehicle."; + p.th_overhang_distance = getOrDeclareParameter(*node, ns + "th_overhang_distance"); + } + { const std::string ns = "avoidance.target_filtering.avoidance_for_ambiguous_vehicle."; p.enable_avoidance_for_ambiguous_vehicle = getOrDeclareParameter(*node, ns + "enable"); @@ -378,11 +383,24 @@ AvoidanceParameters getParameter(rclcpp::Node * node) // debug { const std::string ns = "avoidance.debug."; - p.publish_debug_marker = getOrDeclareParameter(*node, ns + "marker"); + p.enable_other_objects_marker = + getOrDeclareParameter(*node, ns + "enable_other_objects_marker"); + p.enable_other_objects_info = + getOrDeclareParameter(*node, ns + "enable_other_objects_info"); + p.enable_detection_area_marker = + getOrDeclareParameter(*node, ns + "enable_detection_area_marker"); + p.enable_drivable_bound_marker = + getOrDeclareParameter(*node, ns + "enable_drivable_bound_marker"); + p.enable_safety_check_marker = + getOrDeclareParameter(*node, ns + "enable_safety_check_marker"); + p.enable_shift_line_marker = + getOrDeclareParameter(*node, ns + "enable_shift_line_marker"); + p.enable_lane_marker = getOrDeclareParameter(*node, ns + "enable_lane_marker"); + p.enable_misc_marker = getOrDeclareParameter(*node, ns + "enable_misc_marker"); } return p; } } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__PARAMETER_HELPER_HPP_ +#endif // AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__PARAMETER_HELPER_HPP_ diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp b/planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/scene.hpp similarity index 78% rename from planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/scene.hpp index 899ec99cb0d3b..57090e9f551cf 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/scene.hpp @@ -12,12 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_AVOIDANCE_MODULE__SCENE_HPP_ -#define BEHAVIOR_PATH_AVOIDANCE_MODULE__SCENE_HPP_ +#ifndef AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__SCENE_HPP_ +#define AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__SCENE_HPP_ -#include "behavior_path_avoidance_module/data_structs.hpp" -#include "behavior_path_avoidance_module/helper.hpp" -#include "behavior_path_avoidance_module/shift_line_generator.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/data_structs.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/helper.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/shift_line_generator.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/type_alias.hpp" #include "behavior_path_planner_common/interface/scene_module_interface.hpp" #include "behavior_path_planner_common/interface/scene_module_visitor.hpp" @@ -25,31 +26,23 @@ #include #include -#include -#include -#include -#include -#include - +#include #include #include #include +#include #include namespace behavior_path_planner { -using motion_utils::calcSignedArcLength; -using motion_utils::findNearestIndex; - +using helper::static_obstacle_avoidance::AvoidanceHelper; using tier4_planning_msgs::msg::AvoidanceDebugMsg; -using helper::avoidance::AvoidanceHelper; - -class AvoidanceModule : public SceneModuleInterface +class StaticObstacleAvoidanceModule : public SceneModuleInterface { public: - AvoidanceModule( + StaticObstacleAvoidanceModule( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & @@ -72,7 +65,14 @@ class AvoidanceModule : public SceneModuleInterface std::shared_ptr get_debug_msg_array() const; private: - bool isSatisfiedSuccessCondition(const AvoidancePlanningData & data) const; + /** + * @brief return the result whether the module can stop path generation process. + * @param avoidance data. + * @return it will return AvoidanceState::RUNNING when there are obstacles ego should avoid. + * it will return AvoidanceState::CANCEL when all obstacles have gone. + * it will return AvoidanceState::SUCCEEDED when the ego avoid all obstacles. + */ + AvoidanceState getCurrentModuleState(const AvoidancePlanningData & data) const; bool canTransitSuccessState() override; @@ -86,15 +86,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; } @@ -114,10 +116,10 @@ class AvoidanceModule : public SceneModuleInterface for (const auto & left_shift : left_shift_array_) { const double start_distance = - calcSignedArcLength(path.points, ego_idx, left_shift.start_pose.position); + 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}, @@ -127,10 +129,10 @@ class AvoidanceModule : public SceneModuleInterface for (const auto & right_shift : right_shift_array_) { const double start_distance = - calcSignedArcLength(path.points, ego_idx, right_shift.start_pose.position); + 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}, @@ -145,9 +147,15 @@ class AvoidanceModule : public SceneModuleInterface void removeCandidateRTCStatus() { if (rtc_interface_ptr_map_.at("left")->isRegistered(candidate_uuid_)) { - rtc_interface_ptr_map_.at("left")->removeCooperateStatus(candidate_uuid_); - } else if (rtc_interface_ptr_map_.at("right")->isRegistered(candidate_uuid_)) { - rtc_interface_ptr_map_.at("right")->removeCooperateStatus(candidate_uuid_); + rtc_interface_ptr_map_.at("left")->updateCooperateStatus( + candidate_uuid_, true, State::FAILED, std::numeric_limits::lowest(), + std::numeric_limits::lowest(), clock_->now()); + } + + if (rtc_interface_ptr_map_.at("right")->isRegistered(candidate_uuid_)) { + rtc_interface_ptr_map_.at("right")->updateCooperateStatus( + candidate_uuid_, true, State::FAILED, std::numeric_limits::lowest(), + std::numeric_limits::lowest(), clock_->now()); } } @@ -188,14 +196,6 @@ class AvoidanceModule : public SceneModuleInterface */ void updateRTCData(); - // ego state check - - /** - * @brief update ego status based on avoidance path and surround condition. - * @param ego status. (NOT_AVOID, AVOID, YIELD, AVOID_EXECUTE, AVOID_PATH_NOT_READY) - */ - AvoidanceState updateEgoState(const AvoidancePlanningData & data) const; - // ego behavior update /** @@ -359,7 +359,7 @@ class AvoidanceModule : public SceneModuleInterface * @brief reset registered shift lines. * @details reset only when the base offset is zero. Otherwise, sudden steering will be caused; */ - void removeRegisteredShiftLines() + void removeRegisteredShiftLines(const uint8_t state) { constexpr double threshold = 0.1; if (std::abs(path_shifter_.getBaseOffset()) > threshold) { @@ -369,10 +369,25 @@ class AvoidanceModule : public SceneModuleInterface unlockNewModuleLaunch(); + for (const auto & left_shift : left_shift_array_) { + if (rtc_interface_ptr_map_.at("left")->isRegistered(left_shift.uuid)) { + rtc_interface_ptr_map_.at("left")->updateCooperateStatus( + left_shift.uuid, true, state, std::numeric_limits::lowest(), + std::numeric_limits::lowest(), clock_->now()); + } + } + + for (const auto & right_shift : right_shift_array_) { + if (rtc_interface_ptr_map_.at("right")->isRegistered(right_shift.uuid)) { + rtc_interface_ptr_map_.at("right")->updateCooperateStatus( + right_shift.uuid, true, state, std::numeric_limits::lowest(), + std::numeric_limits::lowest(), clock_->now()); + } + } + if (!path_shifter_.getShiftLines().empty()) { left_shift_array_.clear(); right_shift_array_.clear(); - removeRTCStatus(); } generator_.reset(); @@ -409,7 +424,7 @@ class AvoidanceModule : public SceneModuleInterface std::shared_ptr parameters_; - utils::avoidance::ShiftLineGenerator generator_; + utils::static_obstacle_avoidance::ShiftLineGenerator generator_; AvoidancePlanningData avoid_data_; @@ -424,9 +439,6 @@ class AvoidanceModule : public SceneModuleInterface // TODO(Satoshi OTA) create detected object manager. ObjectDataArray registered_objects_; - // TODO(Satoshi OTA) remove mutable. - mutable ObjectDataArray detected_objects_; - // TODO(Satoshi OTA) remove this variable. mutable ObjectDataArray ego_stopped_objects_; @@ -446,4 +458,4 @@ class AvoidanceModule : public SceneModuleInterface } // namespace behavior_path_planner -#endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__SCENE_HPP_ +#endif // AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__SCENE_HPP_ diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/shift_line_generator.hpp b/planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/shift_line_generator.hpp similarity index 91% rename from planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/shift_line_generator.hpp rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/shift_line_generator.hpp index efdda622a664c..21eaef884b5e6 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/shift_line_generator.hpp +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/shift_line_generator.hpp @@ -12,20 +12,21 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_AVOIDANCE_MODULE__SHIFT_LINE_GENERATOR_HPP_ -#define BEHAVIOR_PATH_AVOIDANCE_MODULE__SHIFT_LINE_GENERATOR_HPP_ +#ifndef AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__SHIFT_LINE_GENERATOR_HPP_ +#define AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__SHIFT_LINE_GENERATOR_HPP_ -#include "behavior_path_avoidance_module/data_structs.hpp" -#include "behavior_path_avoidance_module/helper.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/data_structs.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/helper.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/type_alias.hpp" #include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" #include -namespace behavior_path_planner::utils::avoidance +namespace behavior_path_planner::utils::static_obstacle_avoidance { using behavior_path_planner::PathShifter; -using behavior_path_planner::helper::avoidance::AvoidanceHelper; +using behavior_path_planner::helper::static_obstacle_avoidance::AvoidanceHelper; class ShiftLineGenerator { @@ -241,6 +242,6 @@ class ShiftLineGenerator double base_offset_{0.0}; }; -} // namespace behavior_path_planner::utils::avoidance +} // namespace behavior_path_planner::utils::static_obstacle_avoidance -#endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__SHIFT_LINE_GENERATOR_HPP_ +#endif // AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__SHIFT_LINE_GENERATOR_HPP_ diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/type_alias.hpp b/planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/type_alias.hpp new file mode 100644 index 0000000000000..afdfba30ce267 --- /dev/null +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/type_alias.hpp @@ -0,0 +1,74 @@ +// 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_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__TYPE_ALIAS_HPP_ +#define AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__TYPE_ALIAS_HPP_ + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +namespace behavior_path_planner +{ +// auto msgs +using autoware_auto_perception_msgs::msg::PredictedObject; +using autoware_auto_perception_msgs::msg::PredictedPath; +using autoware_auto_planning_msgs::msg::PathWithLaneId; + +// ROS 2 general msgs +using geometry_msgs::msg::Point; +using geometry_msgs::msg::Pose; +using geometry_msgs::msg::TransformStamped; +using geometry_msgs::msg::Vector3; +using std_msgs::msg::ColorRGBA; +using visualization_msgs::msg::Marker; +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; +using tier4_autoware_utils::calcDistance2d; +using tier4_autoware_utils::calcLateralDeviation; +using tier4_autoware_utils::calcOffsetPose; +using tier4_autoware_utils::calcYawDeviation; +using tier4_autoware_utils::createDefaultMarker; +using tier4_autoware_utils::createMarkerColor; +using tier4_autoware_utils::createMarkerScale; +using tier4_autoware_utils::createPoint; +using tier4_autoware_utils::createQuaternionFromRPY; +using tier4_autoware_utils::getPoint; +using tier4_autoware_utils::getPose; +using tier4_autoware_utils::Point2d; +using tier4_autoware_utils::Polygon2d; +using tier4_autoware_utils::pose2transform; +using tier4_autoware_utils::toHexString; +} // namespace behavior_path_planner + +#endif // AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__TYPE_ALIAS_HPP_ diff --git a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp b/planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/utils.hpp similarity index 94% rename from planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/utils.hpp index 92e9da61c4ada..420edd17ca372 100644 --- a/planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/utils.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef BEHAVIOR_PATH_AVOIDANCE_MODULE__UTILS_HPP_ -#define BEHAVIOR_PATH_AVOIDANCE_MODULE__UTILS_HPP_ +#ifndef AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__UTILS_HPP_ +#define AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__UTILS_HPP_ -#include "behavior_path_avoidance_module/data_structs.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/data_structs.hpp" #include "behavior_path_planner_common/data_manager.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" @@ -23,8 +23,9 @@ #include #include -namespace behavior_path_planner::utils::avoidance +namespace behavior_path_planner::utils::static_obstacle_avoidance { + using behavior_path_planner::PlannerData; using behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObject; using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityAndPolygonStamped; @@ -115,8 +116,6 @@ void fillObjectStoppableJudge( ObjectData & object_data, const ObjectDataArray & registered_objects, const double feasible_stop_distance, const std::shared_ptr & parameters); -void fillInitialPose(ObjectData & object_data, ObjectDataArray & detected_objects); - void updateRegisteredObject( ObjectDataArray & registered_objects, const ObjectDataArray & now_objects, const std::shared_ptr & parameters); @@ -175,6 +174,6 @@ double calcDistanceToAvoidStartLine( const std::shared_ptr & planner_data, const std::shared_ptr & parameters); -} // namespace behavior_path_planner::utils::avoidance +} // namespace behavior_path_planner::utils::static_obstacle_avoidance -#endif // BEHAVIOR_PATH_AVOIDANCE_MODULE__UTILS_HPP_ +#endif // AUTOWARE_BEHAVIOR_PATH_STATIC_OBSTACLE_AVOIDANCE_MODULE__UTILS_HPP_ diff --git a/planning/behavior_path_avoidance_module/package.xml b/planning/autoware_behavior_path_static_obstacle_avoidance_module/package.xml similarity index 90% rename from planning/behavior_path_avoidance_module/package.xml rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/package.xml index fc34172bb2ce9..3643257d243b4 100644 --- a/planning/behavior_path_avoidance_module/package.xml +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/package.xml @@ -1,9 +1,9 @@ - behavior_path_avoidance_module + autoware_behavior_path_static_obstacle_avoidance_module 0.1.0 - The behavior_path_avoidance_module package + The autoware_behavior_path_static_obstacle_avoidance_module package Takamasa Horibe Zulfaqar Azmi @@ -13,6 +13,7 @@ Tomoya Kimura Shumpei Wakabayashi Tomohito Ando + Go Sakayori Apache License 2.0 diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/plugins.xml b/planning/autoware_behavior_path_static_obstacle_avoidance_module/plugins.xml new file mode 100644 index 0000000000000..a4e1da9d5dccb --- /dev/null +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/plugins.xml @@ -0,0 +1,3 @@ + + + diff --git a/planning/behavior_path_avoidance_module/schema/avoidance.schema.json b/planning/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json similarity index 95% rename from planning/behavior_path_avoidance_module/schema/avoidance.schema.json rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json index eee34edbc0e0c..e0f1156172932 100644 --- a/planning/behavior_path_avoidance_module/schema/avoidance.schema.json +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/schema/static_obstacle_avoidance.schema.json @@ -681,6 +681,18 @@ ], "additionalProperties": false }, + "merging_vehicle": { + "type": "object", + "properties": { + "th_overhang_distance": { + "type": "number", + "description": "Distance threshold to ignore merging/deviating vehicle to/from ego driving lane. The distance represents how the object polygon overlaps ego lane, and it's calculated from polygon overhang point and lane centerline. If the distance is more than this param, the module never avoid the object. (Basically, the ego stops behind of it.)", + "default": 0.5 + } + }, + "required": ["th_overhang_distance"], + "additionalProperties": false + }, "parked_vehicle": { "type": "object", "properties": { @@ -803,6 +815,7 @@ "object_check_return_pose_distance", "max_compensation_time", "detection_area", + "merging_vehicle", "parked_vehicle", "avoidance_for_ambiguous_vehicle", "intersection" @@ -1375,13 +1388,57 @@ "debug": { "type": "object", "properties": { - "marker": { + "enable_other_objects_marker": { "type": "boolean", - "description": "Publish debug marker.", + "description": "Publish other objects marker.", + "default": "false" + }, + "enable_other_objects_info": { + "type": "boolean", + "description": "Publish other objects detail information.", + "default": "false" + }, + "enable_detection_area_marker": { + "type": "boolean", + "description": "Publish detection area.", + "default": "false" + }, + "enable_drivable_bound_marker": { + "type": "boolean", + "description": "Publish drivable area boundary.", + "default": "false" + }, + "enable_safety_check_marker": { + "type": "boolean", + "description": "Publish safety check information.", + "default": "false" + }, + "enable_shift_line_marker": { + "type": "boolean", + "description": "Publish shift line information.", + "default": "false" + }, + "enable_lane_marker": { + "type": "boolean", + "description": "Publish lane information.", + "default": "false" + }, + "enable_misc_marker": { + "type": "boolean", + "description": "Publish misc markers.", "default": "false" } }, - "required": ["marker"], + "required": [ + "enable_other_objects_marker", + "enable_other_objects_info", + "enable_detection_area_marker", + "enable_drivable_bound_marker", + "enable_safety_check_marker", + "enable_shift_line_marker", + "enable_lane_marker", + "enable_misc_marker" + ], "additionalProperties": false } }, diff --git a/planning/behavior_path_avoidance_module/src/debug.cpp b/planning/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp similarity index 85% rename from planning/behavior_path_avoidance_module/src/debug.cpp rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp index 7d029277fcbc4..b8e6bb99fbebb 100644 --- a/planning/behavior_path_avoidance_module/src/debug.cpp +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp @@ -12,33 +12,19 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_avoidance_module/debug.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/debug.hpp" #include "behavior_path_planner_common/marker_utils/utils.hpp" #include "behavior_path_planner_common/utils/utils.hpp" #include #include -#include - -#include #include #include -namespace marker_utils::avoidance_marker +namespace behavior_path_planner::utils::static_obstacle_avoidance { - -using tier4_autoware_utils::appendMarkerArray; -using tier4_autoware_utils::calcDistance2d; -using tier4_autoware_utils::calcOffsetPose; -using tier4_autoware_utils::createDefaultMarker; -using tier4_autoware_utils::createMarkerColor; -using tier4_autoware_utils::createMarkerScale; -using tier4_autoware_utils::createPoint; -using tier4_autoware_utils::getPose; -using visualization_msgs::msg::Marker; - namespace { @@ -144,7 +130,8 @@ MarkerArray createToDrivableBoundDistance(const ObjectDataArray & objects, std:: return msg; } -MarkerArray createObjectInfoMarkerArray(const ObjectDataArray & objects, std::string && ns) +MarkerArray createObjectInfoMarkerArray( + const ObjectDataArray & objects, std::string && ns, const bool verbose) { MarkerArray msg; @@ -153,7 +140,7 @@ MarkerArray createObjectInfoMarkerArray(const ObjectDataArray & objects, std::st createMarkerScale(0.5, 0.5, 0.5), createMarkerColor(1.0, 1.0, 0.0, 1.0)); for (const auto & object : objects) { - { + if (verbose) { marker.id = uuidToInt32(object.object.object_id); marker.pose = object.object.kinematics.initial_pose_with_covariance.pose; std::ostringstream string_stream; @@ -174,9 +161,11 @@ MarkerArray createObjectInfoMarkerArray(const ObjectDataArray & objects, std::st { marker.id = uuidToInt32(object.object.object_id); + marker.pose = object.object.kinematics.initial_pose_with_covariance.pose; marker.pose.position.z += 2.0; std::ostringstream string_stream; - string_stream << object.reason << (object.is_parked ? "(PARKED)" : ""); + string_stream << magic_enum::enum_name(object.info) << (object.is_parked ? "(PARKED)" : ""); + string_stream << (object.is_ambiguous ? "(WAIT AND SEE)" : ""); marker.text = string_stream.str(); marker.color = createMarkerColor(1.0, 1.0, 1.0, 0.999); marker.scale = createMarkerScale(0.6, 0.6, 0.6); @@ -214,7 +203,7 @@ MarkerArray avoidableObjectsMarkerArray(const ObjectDataArray & objects, std::st createMarkerColor(1.0, 1.0, 0.0, 0.8)), &msg); - appendMarkerArray(createObjectInfoMarkerArray(objects, ns + "_info"), &msg); + appendMarkerArray(createObjectInfoMarkerArray(objects, ns + "_info", true), &msg); appendMarkerArray(createObjectPolygonMarkerArray(objects, ns + "_envelope_polygon"), &msg); appendMarkerArray(createToDrivableBoundDistance(objects, ns + "_to_drivable_bound"), &msg); appendMarkerArray(createOverhangLaneletMarkerArray(objects, ns + "_overhang_lanelet"), &msg); @@ -233,7 +222,7 @@ MarkerArray unAvoidableObjectsMarkerArray(const ObjectDataArray & objects, std:: createMarkerColor(1.0, 0.0, 0.0, 0.8)), &msg); - appendMarkerArray(createObjectInfoMarkerArray(objects, ns + "_info"), &msg); + appendMarkerArray(createObjectInfoMarkerArray(objects, ns + "_info", true), &msg); appendMarkerArray(createObjectPolygonMarkerArray(objects, ns + "_envelope_polygon"), &msg); appendMarkerArray(createToDrivableBoundDistance(objects, ns + "_to_drivable_bound"), &msg); appendMarkerArray(createOverhangLaneletMarkerArray(objects, ns + "_overhang_lanelet"), &msg); @@ -441,14 +430,13 @@ MarkerArray createTargetObjectsMarkerArray(const ObjectDataArray & objects, cons return msg; } -MarkerArray createOtherObjectsMarkerArray(const ObjectDataArray & objects, const std::string & ns) +MarkerArray createOtherObjectsMarkerArray( + const ObjectDataArray & objects, const ObjectInfo & info, const bool verbose) { - using behavior_path_planner::utils::convertToSnakeCase; - - const auto filtered_objects = [&objects, &ns]() { + const auto filtered_objects = [&objects, &info]() { ObjectDataArray ret{}; for (const auto & o : objects) { - if (o.reason != ns) { + if (o.info != info) { continue; } ret.push_back(o); @@ -460,18 +448,21 @@ MarkerArray createOtherObjectsMarkerArray(const ObjectDataArray & objects, const MarkerArray msg; msg.markers.reserve(filtered_objects.size() * 2); + std::ostringstream string_stream; + string_stream << magic_enum::enum_name(info); + + std::string ns = string_stream.str(); + transform(ns.begin(), ns.end(), ns.begin(), tolower); + appendMarkerArray( createObjectsCubeMarkerArray( - filtered_objects, "others_" + convertToSnakeCase(ns) + "_cube", - createMarkerScale(3.0, 1.5, 1.5), createMarkerColor(0.0, 1.0, 0.0, 0.8)), + filtered_objects, "others_" + ns + "_cube", createMarkerScale(3.0, 1.5, 1.5), + createMarkerColor(0.0, 1.0, 0.0, 0.8)), &msg); appendMarkerArray( - createObjectInfoMarkerArray(filtered_objects, "others_" + convertToSnakeCase(ns) + "_info"), - &msg); + createObjectInfoMarkerArray(filtered_objects, "others_" + ns + "_info", verbose), &msg); appendMarkerArray( - createOverhangLaneletMarkerArray( - filtered_objects, "others_" + convertToSnakeCase(ns) + "_overhang_lanelet"), - &msg); + createOverhangLaneletMarkerArray(filtered_objects, "others_" + ns + "_overhang_lanelet"), &msg); return msg; } @@ -513,7 +504,8 @@ MarkerArray createDrivableBounds( } MarkerArray createDebugMarkerArray( - const AvoidancePlanningData & data, const PathShifter & shifter, const DebugData & debug) + const AvoidancePlanningData & data, const PathShifter & shifter, const DebugData & debug, + const std::shared_ptr & parameters) { using behavior_path_planner::utils::transformToLanelets; using lanelet::visualization::laneletsAsTriangleMarkerArray; @@ -528,7 +520,6 @@ MarkerArray createDebugMarkerArray( using marker_utils::showPolygon; using marker_utils::showPredictedPath; using marker_utils::showSafetyCheckInfo; - using tier4_planning_msgs::msg::AvoidanceDebugFactor; const auto current_time = rclcpp::Clock{RCL_ROS_TIME}.now(); MarkerArray msg; @@ -548,7 +539,7 @@ MarkerArray createDebugMarkerArray( }; const auto addObjects = [&](const ObjectDataArray & objects, const auto & ns) { - add(createOtherObjectsMarkerArray(objects, ns)); + add(createOtherObjectsMarkerArray(objects, ns, parameters->enable_other_objects_info)); }; const auto addShiftLength = @@ -563,28 +554,27 @@ MarkerArray createDebugMarkerArray( }; // ignore objects - { - addObjects(data.other_objects, AvoidanceDebugFactor::OBJECT_IS_BEHIND_THRESHOLD); - addObjects(data.other_objects, AvoidanceDebugFactor::OBJECT_IS_IN_FRONT_THRESHOLD); - addObjects(data.other_objects, AvoidanceDebugFactor::OBJECT_IS_NOT_TYPE); - addObjects(data.other_objects, AvoidanceDebugFactor::OBJECT_BEHIND_PATH_GOAL); - addObjects(data.other_objects, AvoidanceDebugFactor::TOO_NEAR_TO_CENTERLINE); - addObjects(data.other_objects, AvoidanceDebugFactor::NOT_PARKING_OBJECT); - addObjects(data.other_objects, std::string("MovingObject")); - addObjects(data.other_objects, std::string("CrosswalkUser")); - addObjects(data.other_objects, std::string("OutOfTargetArea")); - addObjects(data.other_objects, std::string("NotNeedAvoidance")); - addObjects(data.other_objects, std::string("LessThanExecutionThreshold")); - addObjects(data.other_objects, std::string("TooNearToGoal")); - addObjects(data.other_objects, std::string("ParallelToEgoLane")); - addObjects(data.other_objects, std::string("MergingToEgoLane")); - addObjects(data.other_objects, std::string("UnstableObject")); - addObjects(data.other_objects, std::string("AmbiguousStoppedVehicle")); - addObjects(data.other_objects, std::string("AmbiguousStoppedVehicle(wait-and-see)")); + if (parameters->enable_other_objects_marker) { + addObjects(data.other_objects, ObjectInfo::FURTHER_THAN_THRESHOLD); + addObjects(data.other_objects, ObjectInfo::IS_NOT_TARGET_OBJECT); + addObjects(data.other_objects, ObjectInfo::FURTHER_THAN_GOAL); + addObjects(data.other_objects, ObjectInfo::TOO_NEAR_TO_CENTERLINE); + addObjects(data.other_objects, ObjectInfo::IS_NOT_PARKING_OBJECT); + addObjects(data.other_objects, ObjectInfo::MOVING_OBJECT); + addObjects(data.other_objects, ObjectInfo::CROSSWALK_USER); + addObjects(data.other_objects, ObjectInfo::OUT_OF_TARGET_AREA); + addObjects(data.other_objects, ObjectInfo::ENOUGH_LATERAL_DISTANCE); + addObjects(data.other_objects, ObjectInfo::LESS_THAN_EXECUTION_THRESHOLD); + addObjects(data.other_objects, ObjectInfo::TOO_NEAR_TO_GOAL); + addObjects(data.other_objects, ObjectInfo::PARALLEL_TO_EGO_LANE); + addObjects(data.other_objects, ObjectInfo::MERGING_TO_EGO_LANE); + addObjects(data.other_objects, ObjectInfo::DEVIATING_FROM_EGO_LANE); + addObjects(data.other_objects, ObjectInfo::UNSTABLE_OBJECT); + addObjects(data.other_objects, ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE); } // shift line pre-process - { + if (parameters->enable_shift_line_marker) { addAvoidLine(debug.step1_registered_shift_line, "step1_registered_shift_line", 0.2, 0.2, 1.0); addAvoidLine(debug.step1_current_shift_line, "step1_current_shift_line", 0.2, 0.4, 0.8, 0.3); addAvoidLine(debug.step1_merged_shift_line, "step1_merged_shift_line", 0.2, 0.6, 0.6, 0.3); @@ -593,39 +583,39 @@ MarkerArray createDebugMarkerArray( } // merge process - { + if (parameters->enable_shift_line_marker) { addAvoidLine(debug.step2_merged_shift_line, "step2_merged_shift_line", 0.2, 1.0, 0.0, 0.3); } // trimming process - { + if (parameters->enable_shift_line_marker) { addAvoidLine(debug.step3_grad_filtered_1st, "step3_grad_filtered_1st", 0.2, 0.8, 0.0, 0.3); addAvoidLine(debug.step3_grad_filtered_2nd, "step3_grad_filtered_2nd", 0.4, 0.6, 0.0, 0.3); addAvoidLine(debug.step3_grad_filtered_3rd, "step3_grad_filtered_3rd", 0.6, 0.4, 0.0, 0.3); } // registering process - { + if (parameters->enable_shift_line_marker) { addShiftLine(shifter.getShiftLines(), "step4_old_shift_line", 1.0, 1.0, 0.0, 0.3); addAvoidLine(data.new_shift_line, "step4_new_shift_line", 1.0, 0.0, 0.0, 0.3); } // safety check - { + if (parameters->enable_safety_check_marker) { add(showSafetyCheckInfo(debug.collision_check, "object_debug_info")); add(showPredictedPath(debug.collision_check, "ego_predicted_path")); add(showPolygon(debug.collision_check, "ego_and_target_polygon_relation")); } // shift length - { + if (parameters->enable_shift_line_marker) { addShiftLength(debug.pos_shift, "merged_length_pos", 0.0, 0.7, 0.5); addShiftLength(debug.neg_shift, "merged_length_neg", 0.0, 0.5, 0.7); addShiftLength(debug.total_shift, "merged_length_total", 0.99, 0.4, 0.2); } // shift grad - { + if (parameters->enable_shift_line_marker) { addShiftGrad(debug.pos_shift_grad, debug.pos_shift, "merged_grad_pos", 0.0, 0.7, 0.5); addShiftGrad(debug.neg_shift_grad, debug.neg_shift, "merged_grad_neg", 0.0, 0.5, 0.7); addShiftGrad(debug.total_forward_grad, debug.total_shift, "grad_forward", 0.99, 0.4, 0.2); @@ -633,15 +623,20 @@ MarkerArray createDebugMarkerArray( } // detection area - size_t i = 0; - for (const auto & detection_area : debug.detection_areas) { - add(createPolygonMarkerArray(detection_area, "detection_area", i++, 0.16, 1.0, 0.69, 0.1)); + if (parameters->enable_detection_area_marker) { + size_t i = 0; + for (const auto & detection_area : debug.detection_areas) { + add(createPolygonMarkerArray(detection_area, "detection_area", i++, 0.16, 1.0, 0.69, 0.1)); + } } - // misc - { - add(createPathMarkerArray(path, "centerline_resampled", 0, 0.0, 0.9, 0.5)); + // drivable bound + if (parameters->enable_drivable_bound_marker) { add(createDrivableBounds(data, "drivable_bound", 1.0, 0.0, 0.42)); + } + + // lane + if (parameters->enable_lane_marker) { add(laneletsAsTriangleMarkerArray( "drivable_lanes", transformToLanelets(data.drivable_lanes), createMarkerColor(0.16, 1.0, 0.69, 0.2))); @@ -651,9 +646,14 @@ MarkerArray createDebugMarkerArray( "safety_check_lanes", debug.safety_check_lanes, createMarkerColor(1.0, 0.0, 0.42, 0.2))); } + // misc + if (parameters->enable_misc_marker) { + add(createPathMarkerArray(path, "centerline_resampled", 0, 0.0, 0.9, 0.5)); + } + return msg; } -} // namespace marker_utils::avoidance_marker +} // namespace behavior_path_planner::utils::static_obstacle_avoidance std::string toStrInfo(const behavior_path_planner::ShiftLineArray & sl_arr) { diff --git a/planning/behavior_path_avoidance_module/src/manager.cpp b/planning/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp similarity index 88% rename from planning/behavior_path_avoidance_module/src/manager.cpp rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp index dbff6f60365f3..bfc95e0730cd6 100644 --- a/planning/behavior_path_avoidance_module/src/manager.cpp +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/src/manager.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_avoidance_module/manager.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/manager.hpp" -#include "behavior_path_avoidance_module/parameter_helper.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp" #include "tier4_autoware_utils/ros/parameter.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" @@ -26,7 +26,7 @@ namespace behavior_path_planner { -void AvoidanceModuleManager::init(rclcpp::Node * node) +void StaticObstacleAvoidanceModuleManager::init(rclcpp::Node * node) { using autoware_auto_perception_msgs::msg::ObjectClassification; using tier4_autoware_utils::getOrDeclareParameter; @@ -39,7 +39,8 @@ void AvoidanceModuleManager::init(rclcpp::Node * node) parameters_ = std::make_shared(p); } -void AvoidanceModuleManager::updateModuleParams(const std::vector & parameters) +void StaticObstacleAvoidanceModuleManager::updateModuleParams( + const std::vector & parameters) { using autoware_auto_perception_msgs::msg::ObjectClassification; using tier4_autoware_utils::updateParam; @@ -124,6 +125,11 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector(parameters, ns + "backward_distance", p->object_check_backward_distance); } + { + const std::string ns = "avoidance.target_filtering.merging_vehicle."; + updateParam(parameters, ns + "th_overhang_distance", p->th_overhang_distance); + } + { const std::string ns = "avoidance.avoidance.lateral.avoidance_for_ambiguous_vehicle."; updateParam(parameters, ns + "enable", p->enable_avoidance_for_ambiguous_vehicle); @@ -256,7 +262,17 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector(parameters, ns + "marker", p->publish_debug_marker); + updateParam( + parameters, ns + "enable_other_objects_marker", p->enable_other_objects_marker); + updateParam(parameters, ns + "enable_other_objects_info", p->enable_other_objects_info); + updateParam( + parameters, ns + "enable_detection_area_marker", p->enable_detection_area_marker); + updateParam( + parameters, ns + "enable_drivable_bound_marker", p->enable_drivable_bound_marker); + updateParam(parameters, ns + "enable_safety_check_marker", p->enable_safety_check_marker); + updateParam(parameters, ns + "enable_shift_line_marker", p->enable_shift_line_marker); + updateParam(parameters, ns + "enable_lane_marker", p->enable_lane_marker); + updateParam(parameters, ns + "enable_misc_marker", p->enable_misc_marker); } std::for_each(observers_.begin(), observers_.end(), [&p](const auto & observer) { @@ -267,4 +283,5 @@ void AvoidanceModuleManager::updateModuleParams(const std::vector PLUGINLIB_EXPORT_CLASS( - behavior_path_planner::AvoidanceModuleManager, behavior_path_planner::SceneModuleManagerInterface) + behavior_path_planner::StaticObstacleAvoidanceModuleManager, + behavior_path_planner::SceneModuleManagerInterface) diff --git a/planning/behavior_path_avoidance_module/src/scene.cpp b/planning/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp similarity index 85% rename from planning/behavior_path_avoidance_module/src/scene.cpp rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index 1d46e4e1f9d5d..0a6d490f7fbf1 100644 --- a/planning/behavior_path_avoidance_module/src/scene.cpp +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_avoidance_module/scene.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/scene.hpp" -#include "behavior_path_avoidance_module/debug.hpp" -#include "behavior_path_avoidance_module/utils.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/debug.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/utils.hpp" #include "behavior_path_planner_common/interface/scene_module_visitor.hpp" #include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" @@ -26,12 +26,6 @@ #include #include -#include -#include -#include - -#include "tier4_planning_msgs/msg/detail/avoidance_debug_msg_array__struct.hpp" -#include #include #include @@ -42,18 +36,6 @@ namespace behavior_path_planner { - -using motion_utils::calcLongitudinalOffsetPose; -using motion_utils::calcSignedArcLength; -using motion_utils::findNearestIndex; -using tier4_autoware_utils::appendMarkerArray; -using tier4_autoware_utils::calcDistance2d; -using tier4_autoware_utils::calcLateralDeviation; -using tier4_autoware_utils::getPoint; -using tier4_autoware_utils::getPose; -using tier4_autoware_utils::toHexString; -using tier4_planning_msgs::msg::AvoidanceDebugFactor; - namespace { bool isDrivingSameLane( @@ -89,7 +71,7 @@ lanelet::BasicLineString3d toLineString3d(const std::vector & bound) } } // namespace -AvoidanceModule::AvoidanceModule( +StaticObstacleAvoidanceModule::StaticObstacleAvoidanceModule( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & @@ -101,7 +83,7 @@ AvoidanceModule::AvoidanceModule( { } -bool AvoidanceModule::isExecutionRequested() const +bool StaticObstacleAvoidanceModule::isExecutionRequested() const { RCLCPP_DEBUG(getLogger(), "AVOIDANCE isExecutionRequested"); @@ -119,12 +101,11 @@ bool AvoidanceModule::isExecutionRequested() const } return std::any_of( - avoid_data_.target_objects.begin(), avoid_data_.target_objects.end(), [](const auto & o) { - return o.is_avoidable || o.reason == AvoidanceDebugFactor::TOO_LARGE_JERK; - }); + avoid_data_.target_objects.begin(), avoid_data_.target_objects.end(), + [this](const auto & o) { return !helper_->isAbsolutelyNotAvoidable(o); }); } -bool AvoidanceModule::isExecutionReady() const +bool StaticObstacleAvoidanceModule::isExecutionReady() const { RCLCPP_DEBUG_STREAM(getLogger(), "---Avoidance GO/NO-GO status---"); RCLCPP_DEBUG_STREAM(getLogger(), std::boolalpha << "SAFE:" << avoid_data_.safe); @@ -134,15 +115,15 @@ bool AvoidanceModule::isExecutionReady() const return avoid_data_.safe && avoid_data_.comfortable && avoid_data_.valid && avoid_data_.ready; } -bool AvoidanceModule::isSatisfiedSuccessCondition(const AvoidancePlanningData & data) const +AvoidanceState StaticObstacleAvoidanceModule::getCurrentModuleState( + const AvoidancePlanningData & data) const { - const bool has_avoidance_target = - std::any_of(data.target_objects.begin(), data.target_objects.end(), [](const auto & o) { - return o.is_avoidable || o.reason == AvoidanceDebugFactor::TOO_LARGE_JERK; - }); + const bool has_avoidance_target = std::any_of( + data.target_objects.begin(), data.target_objects.end(), + [this](const auto & o) { return !helper_->isAbsolutelyNotAvoidable(o); }); if (has_avoidance_target) { - return false; + return AvoidanceState::RUNNING; } // If the ego is on the shift line, keep RUNNING. @@ -153,7 +134,7 @@ bool AvoidanceModule::isSatisfiedSuccessCondition(const AvoidancePlanningData & }; for (const auto & shift_line : path_shifter_.getShiftLines()) { if (within(shift_line, idx)) { - return false; + return AvoidanceState::RUNNING; } } } @@ -162,20 +143,24 @@ bool AvoidanceModule::isSatisfiedSuccessCondition(const AvoidancePlanningData & const bool has_base_offset = std::abs(path_shifter_.getBaseOffset()) > parameters_->lateral_execution_threshold; + if (has_base_offset) { + return AvoidanceState::RUNNING; + } + // Nothing to do. -> EXIT. - if (!has_shift_point && !has_base_offset) { - return true; + if (!has_shift_point) { + return AvoidanceState::SUCCEEDED; } // Be able to canceling avoidance path. -> EXIT. if (!helper_->isShifted() && parameters_->enable_cancel_maneuver) { - return true; + return AvoidanceState::CANCEL; } - return false; + return AvoidanceState::RUNNING; } -bool AvoidanceModule::canTransitSuccessState() +bool StaticObstacleAvoidanceModule::canTransitSuccessState() { const auto & data = avoid_data_; @@ -203,25 +188,26 @@ bool AvoidanceModule::canTransitSuccessState() } } - return data.success; + return data.state == AvoidanceState::CANCEL || data.state == AvoidanceState::SUCCEEDED; } -void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugData & debug) +void StaticObstacleAvoidanceModule::fillFundamentalData( + AvoidancePlanningData & data, DebugData & debug) { // reference pose data.reference_pose = utils::getUnshiftedEgoPose(getEgoPose(), helper_->getPreviousSplineShiftPath()); // lanelet info - data.current_lanelets = utils::avoidance::getCurrentLanesFromPath( + data.current_lanelets = utils::static_obstacle_avoidance::getCurrentLanesFromPath( getPreviousModuleOutput().reference_path, planner_data_); - data.extend_lanelets = - utils::avoidance::getExtendLanes(data.current_lanelets, getEgoPose(), planner_data_); + data.extend_lanelets = utils::static_obstacle_avoidance::getExtendLanes( + data.current_lanelets, getEgoPose(), planner_data_); // expand drivable lanes const auto is_within_current_lane = - utils::avoidance::isWithinLanes(data.current_lanelets, planner_data_); + utils::static_obstacle_avoidance::isWithinLanes(data.current_lanelets, planner_data_); const auto red_signal_lane_itr = std::find_if( data.current_lanelets.begin(), data.current_lanelets.end(), [&](const auto & lanelet) { const auto next_lanes = planner_data_->route_handler->getNextLanelets(lanelet); @@ -234,12 +220,15 @@ void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugDat data.current_lanelets.begin(), data.current_lanelets.end(), [&](const auto & lanelet) { if (!not_use_adjacent_lane) { data.drivable_lanes.push_back( - utils::avoidance::generateExpandedDrivableLanes(lanelet, planner_data_, parameters_)); + utils::static_obstacle_avoidance::generateExpandedDrivableLanes( + lanelet, planner_data_, parameters_)); } else if (red_signal_lane_itr->id() != lanelet.id()) { data.drivable_lanes.push_back( - utils::avoidance::generateExpandedDrivableLanes(lanelet, planner_data_, parameters_)); + utils::static_obstacle_avoidance::generateExpandedDrivableLanes( + lanelet, planner_data_, parameters_)); } else { - data.drivable_lanes.push_back(utils::avoidance::generateNotExpandedDrivableLanes(lanelet)); + data.drivable_lanes.push_back( + utils::static_obstacle_avoidance::generateNotExpandedDrivableLanes(lanelet)); } }); @@ -285,20 +274,21 @@ void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugDat // arclength from ego pose (used in many functions) data.arclength_from_ego = utils::calcPathArcLengthArray( data.reference_path, 0, data.reference_path.points.size(), - calcSignedArcLength(data.reference_path.points, getEgoPosition(), 0)); + motion_utils::calcSignedArcLength(data.reference_path.points, getEgoPosition(), 0)); - data.to_return_point = utils::avoidance::calcDistanceToReturnDeadLine( + data.to_return_point = utils::static_obstacle_avoidance::calcDistanceToReturnDeadLine( data.current_lanelets, data.reference_path_rough, planner_data_, parameters_); - data.to_start_point = utils::avoidance::calcDistanceToAvoidStartLine( + data.to_start_point = utils::static_obstacle_avoidance::calcDistanceToAvoidStartLine( data.current_lanelets, data.reference_path_rough, planner_data_, parameters_); // target objects for avoidance fillAvoidanceTargetObjects(data, debug); // lost object compensation - utils::avoidance::updateRegisteredObject(registered_objects_, data.target_objects, parameters_); - utils::avoidance::compensateDetectionLost( + utils::static_obstacle_avoidance::updateRegisteredObject( + registered_objects_, data.target_objects, parameters_); + utils::static_obstacle_avoidance::compensateDetectionLost( registered_objects_, data.target_objects, data.other_objects); // sort object order by longitudinal distance @@ -310,14 +300,14 @@ void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugDat path_shifter_.setPath(data.reference_path); } -void AvoidanceModule::fillAvoidanceTargetObjects( +void StaticObstacleAvoidanceModule::fillAvoidanceTargetObjects( AvoidancePlanningData & data, DebugData & debug) const { - using utils::avoidance::fillAvoidanceNecessity; - using utils::avoidance::fillObjectStoppableJudge; - using utils::avoidance::filterTargetObjects; - using utils::avoidance::separateObjectsByPath; - using utils::avoidance::updateRoadShoulderDistance; + using utils::static_obstacle_avoidance::fillAvoidanceNecessity; + using utils::static_obstacle_avoidance::fillObjectStoppableJudge; + using utils::static_obstacle_avoidance::filterTargetObjects; + using utils::static_obstacle_avoidance::separateObjectsByPath; + using utils::static_obstacle_avoidance::updateRoadShoulderDistance; using utils::traffic_light::calcDistanceToRedTrafficLight; // Separate dynamic objects based on whether they are inside or outside of the expanded lanelets. @@ -337,7 +327,7 @@ void AvoidanceModule::fillAvoidanceTargetObjects( for (const auto & object : object_outside_target_lane.objects) { ObjectData other_object = createObjectData(data, object); - other_object.reason = "OutOfTargetArea"; + other_object.info = ObjectInfo::OUT_OF_TARGET_AREA; data.other_objects.push_back(other_object); } @@ -367,8 +357,6 @@ void AvoidanceModule::fillAvoidanceTargetObjects( debug_info.object_id = toHexString(o.object.object_id); debug_info.longitudinal_distance = o.longitudinal; debug_info.lateral_distance_from_centerline = o.to_centerline; - debug_info.allow_avoidance = o.reason == ""; - debug_info.failed_reason = o.reason; debug_info_array.push_back(debug_info); }; @@ -378,14 +366,15 @@ void AvoidanceModule::fillAvoidanceTargetObjects( } } -ObjectData AvoidanceModule::createObjectData( +ObjectData StaticObstacleAvoidanceModule::createObjectData( const AvoidancePlanningData & data, const PredictedObject & object) const { using boost::geometry::return_centroid; const auto & path_points = data.reference_path.points; const auto & object_pose = object.kinematics.initial_pose_with_covariance.pose; - const auto object_closest_index = findNearestIndex(path_points, object_pose.position); + const auto object_closest_index = + motion_utils::findNearestIndex(path_points, object_pose.position); const auto object_closest_pose = path_points.at(object_closest_index).point.pose; const auto object_type = utils::getHighestProbLabel(object.classification); const auto object_parameter = parameters_->object_parameters.at(object_type); @@ -401,17 +390,15 @@ ObjectData AvoidanceModule::createObjectData( object_data.distance_factor = object_parameter.max_expand_ratio * clamp + 1.0; // Calc envelop polygon. - utils::avoidance::fillObjectEnvelopePolygon( + utils::static_obstacle_avoidance::fillObjectEnvelopePolygon( object_data, registered_objects_, object_closest_pose, parameters_); // calc object centroid. object_data.centroid = return_centroid(object_data.envelope_poly); // Calc moving time. - utils::avoidance::fillObjectMovingTime(object_data, stopped_objects_, parameters_); - - // Fill init pose. - utils::avoidance::fillInitialPose(object_data, detected_objects_); + utils::static_obstacle_avoidance::fillObjectMovingTime( + object_data, stopped_objects_, parameters_); // Calc lateral deviation from path to target object. object_data.direction = calcLateralDeviation(object_closest_pose, object_pose.position) > 0.0 @@ -421,7 +408,7 @@ ObjectData AvoidanceModule::createObjectData( return object_data; } -bool AvoidanceModule::canYieldManeuver(const AvoidancePlanningData & data) const +bool StaticObstacleAvoidanceModule::canYieldManeuver(const AvoidancePlanningData & data) const { // transit yield maneuver only when the avoidance maneuver is not initiated. if (helper_->isShifted()) { @@ -433,9 +420,9 @@ bool AvoidanceModule::canYieldManeuver(const AvoidancePlanningData & data) const const auto registered_lines = path_shifter_.getShiftLines(); if (!registered_lines.empty()) { const size_t idx = planner_data_->findEgoIndex(path_shifter_.getReferencePath().points); - const auto to_shift_start_point = calcSignedArcLength( + const auto prepare_distance = motion_utils::calcSignedArcLength( path_shifter_.getReferencePath().points, idx, registered_lines.front().start_idx); - if (to_shift_start_point < helper_->getMinimumPrepareDistance()) { + if (!helper_->isEnoughPrepareDistance(prepare_distance)) { RCLCPP_DEBUG( getLogger(), "Distance to shift start point is less than minimum prepare distance. The distance is not " @@ -473,7 +460,8 @@ bool AvoidanceModule::canYieldManeuver(const AvoidancePlanningData & data) const return true; } -void AvoidanceModule::fillShiftLine(AvoidancePlanningData & data, DebugData & debug) const +void StaticObstacleAvoidanceModule::fillShiftLine( + AvoidancePlanningData & data, DebugData & debug) const { auto path_shifter = path_shifter_; @@ -505,12 +493,13 @@ void AvoidanceModule::fillShiftLine(AvoidancePlanningData & data, DebugData & de /** * STEP4: Generate avoidance path. */ - ShiftedPath spline_shift_path = utils::avoidance::toShiftedPath(data.reference_path); + ShiftedPath spline_shift_path = + utils::static_obstacle_avoidance::toShiftedPath(data.reference_path); const auto success_spline_path_generation = path_shifter.generate(&spline_shift_path, true, SHIFT_TYPE::SPLINE); data.candidate_path = success_spline_path_generation ? spline_shift_path - : utils::avoidance::toShiftedPath(data.reference_path); + : utils::static_obstacle_avoidance::toShiftedPath(data.reference_path); /** * STEP5: Check avoidance path safety. @@ -523,22 +512,21 @@ void AvoidanceModule::fillShiftLine(AvoidancePlanningData & data, DebugData & de helper_->isReady(data.target_objects); } -void AvoidanceModule::fillEgoStatus( +void StaticObstacleAvoidanceModule::fillEgoStatus( AvoidancePlanningData & data, [[maybe_unused]] DebugData & debug) const { - data.success = isSatisfiedSuccessCondition(data); + data.state = getCurrentModuleState(data); /** * Find the nearest object that should be avoid. When the ego follows reference path, * if the both of following two conditions are satisfied, the module surely avoid the object. * Condition1: there is risk to collide with object without avoidance. * Condition2: there is enough space to avoid. - * In TOO_LARGE_JERK condition, it is possible to avoid object by deceleration even if the flag + * In NEED_DECELERATION condition, it is possible to avoid object by deceleration even if the flag * is_avoidable is FALSE. So, the module inserts stop point for such a object. */ for (const auto & o : data.target_objects) { - const auto enough_space = o.is_avoidable || o.reason == AvoidanceDebugFactor::TOO_LARGE_JERK; - if (o.avoid_required && enough_space) { + if (o.avoid_required && !helper_->isAbsolutelyNotAvoidable(o)) { data.avoid_required = true; data.stop_target_object = o; data.to_stop_line = o.to_stop_line; @@ -618,7 +606,7 @@ void AvoidanceModule::fillEgoStatus( } } -void AvoidanceModule::fillDebugData( +void StaticObstacleAvoidanceModule::fillDebugData( const AvoidancePlanningData & data, [[maybe_unused]] DebugData & debug) const { if (!data.stop_target_object) { @@ -645,12 +633,12 @@ void AvoidanceModule::fillDebugData( 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( - helper_->getShiftLength(o_front, utils::avoidance::isOnRight(o_front), max_avoid_margin)); + const auto avoidance_distance = helper_->getSharpAvoidanceDistance(helper_->getShiftLength( + o_front, utils::static_obstacle_avoidance::isOnRight(o_front), max_avoid_margin)); const auto prepare_distance = helper_->getNominalPrepareDistance(); const auto total_avoid_distance = prepare_distance + avoidance_distance + constant_distance; - dead_pose_ = calcLongitudinalOffsetPose( + dead_pose_ = motion_utils::calcLongitudinalOffsetPose( data.reference_path.points, getEgoPosition(), o_front.longitudinal - total_avoid_distance); if (!dead_pose_) { @@ -658,28 +646,8 @@ void AvoidanceModule::fillDebugData( } } -AvoidanceState AvoidanceModule::updateEgoState(const AvoidancePlanningData & data) const -{ - if (data.yield_required) { - return AvoidanceState::YIELD; - } - - if (!data.avoid_required) { - return AvoidanceState::NOT_AVOID; - } - - if (!data.found_avoidance_path) { - return AvoidanceState::AVOID_PATH_NOT_READY; - } - - if (isWaitingApproval() && path_shifter_.getShiftLines().empty()) { - return AvoidanceState::AVOID_PATH_READY; - } - - return AvoidanceState::AVOID_EXECUTE; -} - -void AvoidanceModule::updateEgoBehavior(const AvoidancePlanningData & data, ShiftedPath & path) +void StaticObstacleAvoidanceModule::updateEgoBehavior( + const AvoidancePlanningData & data, ShiftedPath & path) { if (parameters_->disable_path_update) { return; @@ -688,36 +656,37 @@ void AvoidanceModule::updateEgoBehavior(const AvoidancePlanningData & data, Shif insertPrepareVelocity(path); insertAvoidanceVelocity(path); - switch (data.state) { - case AvoidanceState::NOT_AVOID: { - break; - } - case AvoidanceState::YIELD: { + const auto insert_velocity = [this, &data, &path]() { + if (data.yield_required) { insertWaitPoint(isBestEffort(parameters_->policy_deceleration), path); - break; + return; } - case AvoidanceState::AVOID_PATH_NOT_READY: { - insertWaitPoint(isBestEffort(parameters_->policy_deceleration), path); - break; + + if (!data.avoid_required) { + return; } - case AvoidanceState::AVOID_PATH_READY: { + + if (!data.found_avoidance_path) { insertWaitPoint(isBestEffort(parameters_->policy_deceleration), path); - break; + return; } - case AvoidanceState::AVOID_EXECUTE: { - insertStopPoint(isBestEffort(parameters_->policy_deceleration), path); - break; + + if (isWaitingApproval() && path_shifter_.getShiftLines().empty()) { + insertWaitPoint(isBestEffort(parameters_->policy_deceleration), path); + return; } - default: - throw std::domain_error("invalid behavior"); - } + + insertStopPoint(isBestEffort(parameters_->policy_deceleration), path); + }; + + insert_velocity(); insertReturnDeadLine(isBestEffort(parameters_->policy_deceleration), path); setStopReason(StopReason::AVOIDANCE, path.path); } -bool AvoidanceModule::isSafePath( +bool StaticObstacleAvoidanceModule::isSafePath( ShiftedPath & shifted_path, [[maybe_unused]] DebugData & debug) const { const auto & p = planner_data_->parameters; @@ -758,8 +727,9 @@ bool AvoidanceModule::isSafePath( const auto hysteresis_factor = safe_ ? 1.0 : parameters_->hysteresis_factor_expand_rate; - const auto safety_check_target_objects = utils::avoidance::getSafetyCheckTargetObjects( - avoid_data_, planner_data_, parameters_, has_left_shift, has_right_shift, debug); + const auto safety_check_target_objects = + utils::static_obstacle_avoidance::getSafetyCheckTargetObjects( + avoid_data_, planner_data_, parameters_, has_left_shift, has_right_shift, debug); if (safety_check_target_objects.empty()) { return true; @@ -823,7 +793,8 @@ bool AvoidanceModule::isSafePath( return safe_ || safe_count_ > parameters_->hysteresis_factor_safe_count; } -PathWithLaneId AvoidanceModule::extendBackwardLength(const PathWithLaneId & original_path) const +PathWithLaneId StaticObstacleAvoidanceModule::extendBackwardLength( + const PathWithLaneId & original_path) const { const auto previous_path = helper_->getPreviousReferencePath(); @@ -837,8 +808,8 @@ PathWithLaneId AvoidanceModule::extendBackwardLength(const PathWithLaneId & orig return a.start_idx < b.start_idx; }); return std::max( - max_dist, - calcSignedArcLength(previous_path.points, lines.front().start.position, getEgoPosition())); + max_dist, motion_utils::calcSignedArcLength( + previous_path.points, lines.front().start.position, getEgoPosition())); }(); const auto extra_margin = 10.0; // Since distance does not consider arclength, but just line. @@ -855,7 +826,9 @@ PathWithLaneId AvoidanceModule::extendBackwardLength(const PathWithLaneId & orig size_t clip_idx = 0; for (size_t i = 0; i < prev_ego_idx; ++i) { - if (backward_length > calcSignedArcLength(previous_path.points, clip_idx, *prev_ego_idx)) { + if ( + backward_length > + motion_utils::calcSignedArcLength(previous_path.points, clip_idx, *prev_ego_idx)) { break; } clip_idx = i; @@ -883,7 +856,7 @@ PathWithLaneId AvoidanceModule::extendBackwardLength(const PathWithLaneId & orig return extended_path; } -BehaviorModuleOutput AvoidanceModule::plan() +BehaviorModuleOutput StaticObstacleAvoidanceModule::plan() { const auto & data = avoid_data_; @@ -892,17 +865,23 @@ BehaviorModuleOutput AvoidanceModule::plan() updatePathShifter(data.safe_shift_line); - if (data.success) { - removeRegisteredShiftLines(); + if (data.state == AvoidanceState::SUCCEEDED) { + removeRegisteredShiftLines(State::SUCCEEDED); + } + + if (data.state == AvoidanceState::CANCEL) { + removeRegisteredShiftLines(State::FAILED); } if (data.yield_required) { - removeRegisteredShiftLines(); + removeRegisteredShiftLines(State::FAILED); } // generate path with shift points that have been inserted. - ShiftedPath linear_shift_path = utils::avoidance::toShiftedPath(data.reference_path); - ShiftedPath spline_shift_path = utils::avoidance::toShiftedPath(data.reference_path); + ShiftedPath linear_shift_path = + utils::static_obstacle_avoidance::toShiftedPath(data.reference_path); + ShiftedPath spline_shift_path = + utils::static_obstacle_avoidance::toShiftedPath(data.reference_path); const auto success_spline_path_generation = path_shifter_.generate(&spline_shift_path, true, SHIFT_TYPE::SPLINE); const auto success_linear_path_generation = @@ -964,8 +943,6 @@ BehaviorModuleOutput AvoidanceModule::plan() spline_shift_path.path, parameters_->resample_interval_for_output); } - avoid_data_.state = updateEgoState(data); - // update output data { updateEgoBehavior(data, spline_shift_path); @@ -993,7 +970,8 @@ BehaviorModuleOutput AvoidanceModule::plan() std::for_each( data.current_lanelets.begin(), data.current_lanelets.end(), [&](const auto & lanelet) { current_drivable_area_info.drivable_lanes.push_back( - utils::avoidance::generateExpandedDrivableLanes(lanelet, planner_data_, parameters_)); + utils::static_obstacle_avoidance::generateExpandedDrivableLanes( + lanelet, planner_data_, parameters_)); }); // expand hatched road markings current_drivable_area_info.enable_expanding_hatched_road_markings = @@ -1013,7 +991,7 @@ BehaviorModuleOutput AvoidanceModule::plan() if (!object.is_avoidable) clip_objects.push_back(object); }); current_drivable_area_info.obstacles = - utils::avoidance::generateObstaclePolygonsForDrivableArea( + utils::static_obstacle_avoidance::generateObstaclePolygonsForDrivableArea( clip_objects, parameters_, planner_data_->parameters.vehicle_width / 2.0); } else { current_drivable_area_info.obstacles.clear(); @@ -1028,7 +1006,7 @@ BehaviorModuleOutput AvoidanceModule::plan() return output; } -CandidateOutput AvoidanceModule::planCandidate() const +CandidateOutput StaticObstacleAvoidanceModule::planCandidate() const { const auto & data = avoid_data_; @@ -1067,7 +1045,7 @@ CandidateOutput AvoidanceModule::planCandidate() const return output; } -BehaviorModuleOutput AvoidanceModule::planWaitingApproval() +BehaviorModuleOutput StaticObstacleAvoidanceModule::planWaitingApproval() { BehaviorModuleOutput out = plan(); @@ -1081,7 +1059,7 @@ BehaviorModuleOutput AvoidanceModule::planWaitingApproval() return out; } -void AvoidanceModule::updatePathShifter(const AvoidLineArray & shift_lines) +void StaticObstacleAvoidanceModule::updatePathShifter(const AvoidLineArray & shift_lines) { if (parameters_->disable_path_update) { return; @@ -1122,10 +1100,10 @@ void AvoidanceModule::updatePathShifter(const AvoidLineArray & shift_lines) /** * set new shift points. remove old shift points if it has a conflict. */ -void AvoidanceModule::addNewShiftLines( +void StaticObstacleAvoidanceModule::addNewShiftLines( PathShifter & path_shifter, const AvoidLineArray & new_shift_lines) const { - ShiftLineArray future = utils::avoidance::toShiftLineArray(new_shift_lines); + ShiftLineArray future = utils::static_obstacle_avoidance::toShiftLineArray(new_shift_lines); size_t min_start_idx = std::numeric_limits::max(); for (const auto & sl : new_shift_lines) { @@ -1188,7 +1166,7 @@ void AvoidanceModule::addNewShiftLines( path_shifter.setLateralAccelerationLimit(helper_->getLateralMaxAccelLimit()); } -bool AvoidanceModule::isValidShiftLine( +bool StaticObstacleAvoidanceModule::isValidShiftLine( const AvoidLineArray & shift_lines, const PathShifter & shifter) const { if (shift_lines.empty()) { @@ -1251,9 +1229,9 @@ bool AvoidanceModule::isValidShiftLine( return true; // valid shift line. } -void AvoidanceModule::updateData() +void StaticObstacleAvoidanceModule::updateData() { - using utils::avoidance::toShiftedPath; + using utils::static_obstacle_avoidance::toShiftedPath; helper_->setData(planner_data_); @@ -1261,7 +1239,7 @@ void AvoidanceModule::updateData() helper_->setPreviousSplineShiftPath(toShiftedPath(getPreviousModuleOutput().path)); helper_->setPreviousLinearShiftPath(toShiftedPath(getPreviousModuleOutput().path)); helper_->setPreviousReferencePath(getPreviousModuleOutput().path); - helper_->setPreviousDrivingLanes(utils::avoidance::getCurrentLanesFromPath( + helper_->setPreviousDrivingLanes(utils::static_obstacle_avoidance::getCurrentLanesFromPath( getPreviousModuleOutput().reference_path, planner_data_)); } @@ -1303,19 +1281,18 @@ void AvoidanceModule::updateData() safe_ = avoid_data_.safe; } -void AvoidanceModule::processOnEntry() +void StaticObstacleAvoidanceModule::processOnEntry() { initVariables(); - removeRTCStatus(); } -void AvoidanceModule::processOnExit() +void StaticObstacleAvoidanceModule::processOnExit() { initVariables(); initRTCStatus(); } -void AvoidanceModule::initVariables() +void StaticObstacleAvoidanceModule::initVariables() { helper_->reset(); generator_.reset(); @@ -1327,7 +1304,7 @@ void AvoidanceModule::initVariables() arrived_path_end_ = false; } -void AvoidanceModule::initRTCStatus() +void StaticObstacleAvoidanceModule::initRTCStatus() { left_shift_array_.clear(); right_shift_array_.clear(); @@ -1336,7 +1313,7 @@ void AvoidanceModule::initRTCStatus() candidate_uuid_ = generateUUID(); } -void AvoidanceModule::updateRTCData() +void StaticObstacleAvoidanceModule::updateRTCData() { const auto & data = avoid_data_; @@ -1371,28 +1348,24 @@ void AvoidanceModule::updateRTCData() updateCandidateRTCStatus(output); } -void AvoidanceModule::updateInfoMarker(const AvoidancePlanningData & data) const +void StaticObstacleAvoidanceModule::updateInfoMarker(const AvoidancePlanningData & data) const { - using marker_utils::avoidance_marker::createTargetObjectsMarkerArray; + using utils::static_obstacle_avoidance::createTargetObjectsMarkerArray; info_marker_.markers.clear(); appendMarkerArray( createTargetObjectsMarkerArray(data.target_objects, "target_objects"), &info_marker_); } -void AvoidanceModule::updateDebugMarker( +void StaticObstacleAvoidanceModule::updateDebugMarker( const AvoidancePlanningData & data, const PathShifter & shifter, const DebugData & debug) const { debug_marker_.markers.clear(); - - if (!parameters_->publish_debug_marker) { - return; - } - - debug_marker_ = marker_utils::avoidance_marker::createDebugMarkerArray(data, shifter, debug); + debug_marker_ = + utils::static_obstacle_avoidance::createDebugMarkerArray(data, shifter, debug, parameters_); } -void AvoidanceModule::updateAvoidanceDebugData( +void StaticObstacleAvoidanceModule::updateAvoidanceDebugData( std::vector & avoidance_debug_msg_array) const { debug_data_.avoidance_debug_msg_array.avoidance_info.clear(); @@ -1409,7 +1382,7 @@ void AvoidanceModule::updateAvoidanceDebugData( } } -double AvoidanceModule::calcDistanceToStopLine(const ObjectData & object) const +double StaticObstacleAvoidanceModule::calcDistanceToStopLine(const ObjectData & object) const { const auto & p = parameters_; const auto & vehicle_width = planner_data_->parameters.vehicle_width; @@ -1438,17 +1411,18 @@ double AvoidanceModule::calcDistanceToStopLine(const ObjectData & object) const : 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)); + const auto avoidance_distance = helper_->getMinAvoidanceDistance(helper_->getShiftLength( + object, utils::static_obstacle_avoidance::isOnRight(object), avoid_margin)); const auto constant_distance = helper_->getFrontConstantDistance(object); + const auto prepare_distance = helper_->getNominalPrepareDistance(0.0); return object.longitudinal - std::min( - avoidance_distance + constant_distance + p->min_prepare_distance + p->stop_buffer, + avoidance_distance + constant_distance + prepare_distance + p->stop_buffer, p->stop_max_distance); } -void AvoidanceModule::insertReturnDeadLine( +void StaticObstacleAvoidanceModule::insertReturnDeadLine( const bool use_constraints_for_decel, ShiftedPath & shifted_path) const { const auto & data = avoid_data_; @@ -1468,18 +1442,18 @@ void AvoidanceModule::insertReturnDeadLine( // Consider the difference in path length between the shifted path and original path (the path // that is shifted inward has a shorter distance to the end of the path than the other one.) const auto & to_reference_path_end = data.arclength_from_ego.back(); - const auto to_shifted_path_end = calcSignedArcLength( + const auto to_shifted_path_end = motion_utils::calcSignedArcLength( shifted_path.path.points, getEgoPosition(), shifted_path.path.points.size() - 1); const auto buffer = std::max(0.0, to_shifted_path_end - to_reference_path_end); const auto min_return_distance = - helper_->getMinAvoidanceDistance(shift_length) + helper_->getMinimumPrepareDistance(); + helper_->getMinAvoidanceDistance(shift_length) + helper_->getNominalPrepareDistance(0.0); const auto to_stop_line = data.to_return_point - min_return_distance - buffer; // If we don't need to consider deceleration constraints, insert a deceleration point // and return immediately if (!use_constraints_for_decel) { - utils::avoidance::insertDecelPoint( + utils::static_obstacle_avoidance::insertDecelPoint( getEgoPosition(), to_stop_line - parameters_->stop_buffer, 0.0, shifted_path.path, stop_pose_); return; @@ -1492,7 +1466,7 @@ void AvoidanceModule::insertReturnDeadLine( return; } - utils::avoidance::insertDecelPoint( + utils::static_obstacle_avoidance::insertDecelPoint( getEgoPosition(), to_stop_line - parameters_->stop_buffer, 0.0, shifted_path.path, stop_pose_); // insert slow down speed. @@ -1505,7 +1479,8 @@ void AvoidanceModule::insertReturnDeadLine( 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); + const auto distance_from_ego = + motion_utils::calcSignedArcLength(shifted_path.path.points, start_idx, i); // slow down speed is inserted only in front of the object. const auto shift_longitudinal_distance = to_stop_line - distance_from_ego; @@ -1524,7 +1499,7 @@ void AvoidanceModule::insertReturnDeadLine( } } -void AvoidanceModule::insertWaitPoint( +void StaticObstacleAvoidanceModule::insertWaitPoint( const bool use_constraints_for_decel, ShiftedPath & shifted_path) const { const auto & data = avoid_data_; @@ -1545,7 +1520,7 @@ void AvoidanceModule::insertWaitPoint( // If we don't need to consider deceleration constraints, insert a deceleration point // and return immediately if (!use_constraints_for_decel) { - utils::avoidance::insertDecelPoint( + utils::static_obstacle_avoidance::insertDecelPoint( getEgoPosition(), data.to_stop_line, 0.0, shifted_path.path, stop_pose_); return; } @@ -1560,7 +1535,7 @@ void AvoidanceModule::insertWaitPoint( // If target object can be stopped for, insert a deceleration point and return if (data.stop_target_object.value().is_stoppable) { - utils::avoidance::insertDecelPoint( + utils::static_obstacle_avoidance::insertDecelPoint( getEgoPosition(), data.to_stop_line, 0.0, shifted_path.path, stop_pose_); return; } @@ -1568,11 +1543,11 @@ void AvoidanceModule::insertWaitPoint( // If the object cannot be stopped for, calculate a "mild" deceleration distance // and insert a deceleration point at that distance const auto stop_distance = helper_->getFeasibleDecelDistance(0.0, false); - utils::avoidance::insertDecelPoint( + utils::static_obstacle_avoidance::insertDecelPoint( getEgoPosition(), stop_distance, 0.0, shifted_path.path, stop_pose_); } -void AvoidanceModule::insertStopPoint( +void StaticObstacleAvoidanceModule::insertStopPoint( const bool use_constraints_for_decel, ShiftedPath & shifted_path) const { const auto & data = avoid_data_; @@ -1599,12 +1574,12 @@ void AvoidanceModule::insertStopPoint( }(); const auto stop_distance = - calcSignedArcLength(shifted_path.path.points, getEgoPosition(), stop_idx); + motion_utils::calcSignedArcLength(shifted_path.path.points, getEgoPosition(), stop_idx); // If we don't need to consider deceleration constraints, insert a deceleration point // and return immediately if (!use_constraints_for_decel) { - utils::avoidance::insertDecelPoint( + utils::static_obstacle_avoidance::insertDecelPoint( getEgoPosition(), stop_distance, 0.0, shifted_path.path, stop_pose_); return; } @@ -1616,11 +1591,11 @@ void AvoidanceModule::insertStopPoint( } constexpr double MARGIN = 1.0; - utils::avoidance::insertDecelPoint( + utils::static_obstacle_avoidance::insertDecelPoint( getEgoPosition(), stop_distance - MARGIN, 0.0, shifted_path.path, stop_pose_); } -void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const +void StaticObstacleAvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const { const auto & data = avoid_data_; @@ -1670,9 +1645,7 @@ void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const return; } - const auto enough_space = - object.value().is_avoidable || object.value().reason == AvoidanceDebugFactor::TOO_LARGE_JERK; - if (!enough_space) { + if (helper_->isAbsolutelyNotAvoidable(object.value())) { return; } @@ -1686,7 +1659,7 @@ void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const 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); + object.value(), utils::static_obstacle_avoidance::isOnRight(object.value()), avoid_margin); // check slow down feasibility const auto min_avoid_distance = helper_->getMinAvoidanceDistance(shift_length); @@ -1704,7 +1677,7 @@ void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const const double current_target_velocity = PathShifter::calcFeasibleVelocityFromJerk( shift_length, helper_->getLateralMinJerkLimit(), distance_to_object); if (current_target_velocity < getEgoSpeed() + parameters_->buf_slow_down_speed) { - utils::avoidance::insertDecelPoint( + utils::static_obstacle_avoidance::insertDecelPoint( getEgoPosition(), decel_distance, parameters_->velocity_map.front(), shifted_path.path, slow_pose_); return; @@ -1712,7 +1685,8 @@ void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const 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); + const auto distance_from_ego = + motion_utils::calcSignedArcLength(shifted_path.path.points, start_idx, i); // slow down speed is inserted only in front of the object. const auto shift_longitudinal_distance = distance_to_object - distance_from_ego; @@ -1733,7 +1707,7 @@ void AvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_path) const shifted_path.path.points, start_idx, distance_to_object); } -void AvoidanceModule::insertAvoidanceVelocity(ShiftedPath & shifted_path) const +void StaticObstacleAvoidanceModule::insertAvoidanceVelocity(ShiftedPath & shifted_path) const { const auto & data = avoid_data_; @@ -1755,7 +1729,8 @@ void AvoidanceModule::insertAvoidanceVelocity(ShiftedPath & shifted_path) const 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); + const auto distance_from_ego = + motion_utils::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; @@ -1779,20 +1754,21 @@ void AvoidanceModule::insertAvoidanceVelocity(ShiftedPath & shifted_path) const shifted_path.path.points, start_idx, distance_to_accel_end_point); } -std::shared_ptr AvoidanceModule::get_debug_msg_array() const +std::shared_ptr StaticObstacleAvoidanceModule::get_debug_msg_array() const { debug_data_.avoidance_debug_msg_array.header.stamp = clock_->now(); return std::make_shared(debug_data_.avoidance_debug_msg_array); } -void AvoidanceModule::acceptVisitor(const std::shared_ptr & visitor) const +void StaticObstacleAvoidanceModule::acceptVisitor( + const std::shared_ptr & visitor) const { if (visitor) { visitor->visitAvoidanceModule(this); } } -void SceneModuleVisitor::visitAvoidanceModule(const AvoidanceModule * module) const +void SceneModuleVisitor::visitAvoidanceModule(const StaticObstacleAvoidanceModule * module) const { avoidance_visitor_ = module->get_debug_msg_array(); } diff --git a/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp b/planning/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp similarity index 92% rename from planning/behavior_path_avoidance_module/src/shift_line_generator.cpp rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp index 9137048945fa1..f9e35ebd4c1b2 100644 --- a/planning/behavior_path_avoidance_module/src/shift_line_generator.cpp +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp @@ -12,22 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_avoidance_module/shift_line_generator.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/shift_line_generator.hpp" -#include "behavior_path_avoidance_module/utils.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/utils.hpp" #include "behavior_path_planner_common/utils/utils.hpp" -#include - -#include - -namespace behavior_path_planner::utils::avoidance +namespace behavior_path_planner::utils::static_obstacle_avoidance { -using tier4_autoware_utils::generateUUID; -using tier4_autoware_utils::getPoint; -using tier4_planning_msgs::msg::AvoidanceDebugFactor; - namespace { bool isBestEffort(const std::string & policy) @@ -131,7 +123,7 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( // use each object param const auto object_type = utils::getHighestProbLabel(object.object.classification); const auto object_parameter = parameters_->object_parameters.at(object_type); - const auto is_object_on_right = utils::avoidance::isOnRight(object); + const auto is_object_on_right = utils::static_obstacle_avoidance::isOnRight(object); // use absolute dist for return-to-center, relative dist from current for avoiding. const auto avoiding_shift = desire_shift_length - current_ego_shift; @@ -182,7 +174,7 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( // prepare distance is not enough. unavoidable. if (avoidance_distance < 1e-3) { - object.reason = AvoidanceDebugFactor::REMAINING_DISTANCE_LESS_THAN_ZERO; + object.info = ObjectInfo::INSUFFICIENT_LONGITUDINAL_DISTANCE; return std::nullopt; } @@ -200,10 +192,10 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( // avoidance distance is not enough. unavoidable. if (!isBestEffort(parameters_->policy_deceleration)) { if (avoidance_distance < helper_->getMinAvoidanceDistance(avoiding_shift) + LON_DIST_BUFFER) { - object.reason = AvoidanceDebugFactor::REMAINING_DISTANCE_LESS_THAN_ZERO; + object.info = ObjectInfo::INSUFFICIENT_LONGITUDINAL_DISTANCE; return std::nullopt; } else { - object.reason = AvoidanceDebugFactor::TOO_LARGE_JERK; + object.info = ObjectInfo::NEED_DECELERATION; return std::nullopt; } } @@ -213,7 +205,7 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( avoidance_distance, helper_->getLateralMaxJerkLimit(), helper_->getAvoidanceEgoSpeed()); if (std::abs(feasible_relative_shift_length) < parameters_->lateral_execution_threshold) { - object.reason = "LessThanExecutionThreshold"; + object.info = ObjectInfo::LESS_THAN_EXECUTION_THRESHOLD; return std::nullopt; } @@ -224,7 +216,7 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( if ( avoidance_distance < helper_->getMinAvoidanceDistance(feasible_shift_length) + LON_DIST_BUFFER) { - object.reason = AvoidanceDebugFactor::REMAINING_DISTANCE_LESS_THAN_ZERO; + object.info = ObjectInfo::INSUFFICIENT_LONGITUDINAL_DISTANCE; return std::nullopt; } @@ -238,7 +230,7 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( 0.5 * data_->parameters.vehicle_width + lateral_hard_margin; if (infeasible) { RCLCPP_DEBUG(rclcpp::get_logger(""), "feasible shift length is not enough to avoid. "); - object.reason = AvoidanceDebugFactor::TOO_LARGE_JERK; + object.info = ObjectInfo::NEED_DECELERATION; return std::nullopt; } @@ -254,7 +246,7 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( AvoidOutlines outlines; for (auto & o : data.target_objects) { if (!o.avoid_margin.has_value()) { - o.reason = AvoidanceDebugFactor::INSUFFICIENT_LATERAL_MARGIN; + o.info = ObjectInfo::INSUFFICIENT_DRIVABLE_SPACE; if (o.avoid_required && is_forward_object(o)) { break; } else { @@ -262,11 +254,12 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( } } - const auto is_object_on_right = utils::avoidance::isOnRight(o); + const auto is_object_on_right = utils::static_obstacle_avoidance::isOnRight(o); const auto desire_shift_length = helper_->getShiftLength(o, is_object_on_right, o.avoid_margin.value()); - if (utils::avoidance::isSameDirectionShift(is_object_on_right, desire_shift_length)) { - o.reason = AvoidanceDebugFactor::SAME_DIRECTION_SHIFT; + if (utils::static_obstacle_avoidance::isSameDirectionShift( + is_object_on_right, desire_shift_length)) { + o.info = ObjectInfo::SAME_DIRECTION_SHIFT; if (o.avoid_required && is_forward_object(o)) { break; } else { @@ -310,7 +303,7 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( return std::clamp(data.to_start_point, nearest_avoid_distance, furthest_avoid_distance); }(); - al_avoid.start_idx = utils::avoidance::findPathIndexFromArclength( + al_avoid.start_idx = utils::static_obstacle_avoidance::findPathIndexFromArclength( data.arclength_from_ego, al_avoid.start_longitudinal + path_front_to_ego); al_avoid.start = data.reference_path.points.at(al_avoid.start_idx).point.pose; al_avoid.start_shift_length = helper_->getLinearShift(al_avoid.start.position); @@ -322,7 +315,7 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( // misc al_avoid.id = generateUUID(); al_avoid.object = o; - al_avoid.object_on_right = utils::avoidance::isOnRight(o); + al_avoid.object_on_right = utils::static_obstacle_avoidance::isOnRight(o); } AvoidLine al_return; @@ -348,7 +341,7 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( // misc al_return.id = generateUUID(); al_return.object = o; - al_return.object_on_right = utils::avoidance::isOnRight(o); + al_return.object_on_right = utils::static_obstacle_avoidance::isOnRight(o); } const bool skip_return_shift = [&]() { @@ -377,14 +370,14 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline( } else if (is_valid_shift_line(al_avoid) && is_valid_shift_line(al_return)) { outlines.emplace_back(al_avoid, al_return); } else { - o.reason = "InvalidShiftLine"; + o.info = ObjectInfo::INVALID_SHIFT_LINE; continue; } o.is_avoidable = true; } - utils::avoidance::fillAdditionalInfoFromLongitudinal(data, outlines); + utils::static_obstacle_avoidance::fillAdditionalInfoFromLongitudinal(data, outlines); debug.step1_current_shift_line = toArray(outlines); @@ -487,7 +480,7 @@ void ShiftLineGenerator::generateTotalShiftLine( const auto & al = avoid_lines.at(j); for (size_t i = 0; i < N; ++i) { // calc current interpolated shift - const auto i_shift = utils::avoidance::lerpShiftLengthOnArc(arcs.at(i), al); + const auto i_shift = utils::static_obstacle_avoidance::lerpShiftLengthOnArc(arcs.at(i), al); // update maximum shift for positive direction if (i_shift > sl.pos_shift_line.at(i)) { @@ -556,8 +549,8 @@ void ShiftLineGenerator::generateTotalShiftLine( AvoidLineArray ShiftLineGenerator::extractShiftLinesFromLine( const AvoidancePlanningData & data, ShiftLineData & shift_line_data) const { - using utils::avoidance::setEndData; - using utils::avoidance::setStartData; + using utils::static_obstacle_avoidance::setEndData; + using utils::static_obstacle_avoidance::setStartData; const auto & path = data.reference_path; const auto & arcs = data.arclength_from_ego; @@ -714,8 +707,9 @@ AvoidOutlines ShiftLineGenerator::applyMergeProcess( } } - utils::avoidance::fillAdditionalInfoFromLongitudinal(data, ret); - utils::avoidance::fillAdditionalInfoFromLongitudinal(data, debug.step1_merged_shift_line); + utils::static_obstacle_avoidance::fillAdditionalInfoFromLongitudinal(data, ret); + utils::static_obstacle_avoidance::fillAdditionalInfoFromLongitudinal( + data, debug.step1_merged_shift_line); return ret; } @@ -757,8 +751,9 @@ AvoidOutlines ShiftLineGenerator::applyFillGapProcess( helper_->alignShiftLinesOrder(outline.middle_lines, false); } - utils::avoidance::fillAdditionalInfoFromLongitudinal(data, ret); - utils::avoidance::fillAdditionalInfoFromLongitudinal(data, debug.step1_filled_shift_line); + utils::static_obstacle_avoidance::fillAdditionalInfoFromLongitudinal(data, ret); + utils::static_obstacle_avoidance::fillAdditionalInfoFromLongitudinal( + data, debug.step1_filled_shift_line); return ret; } @@ -779,7 +774,7 @@ AvoidLineArray ShiftLineGenerator::applyFillGapProcess( // fill gap between ego and nearest shift line. if (sorted.front().start_longitudinal > 0.0) { AvoidLine ego_line{}; - utils::avoidance::setEndData( + utils::static_obstacle_avoidance::setEndData( ego_line, helper_->getEgoLinearShift(), data.reference_pose, data.ego_closest_path_index, 0.0); @@ -803,8 +798,9 @@ AvoidLineArray ShiftLineGenerator::applyFillGapProcess( helper_->alignShiftLinesOrder(ret, false); - utils::avoidance::fillAdditionalInfoFromLongitudinal(data, ret); - utils::avoidance::fillAdditionalInfoFromLongitudinal(data, debug.step1_front_shift_line); + utils::static_obstacle_avoidance::fillAdditionalInfoFromLongitudinal(data, ret); + utils::static_obstacle_avoidance::fillAdditionalInfoFromLongitudinal( + data, debug.step1_front_shift_line); return ret; } @@ -814,7 +810,8 @@ AvoidLineArray ShiftLineGenerator::applyCombineProcess( DebugData & debug) const { debug.step1_registered_shift_line = registered_lines; - return utils::avoidance::combineRawShiftLinesWithUniqueCheck(registered_lines, shift_lines); + return utils::static_obstacle_avoidance::combineRawShiftLinesWithUniqueCheck( + registered_lines, shift_lines); } AvoidLineArray ShiftLineGenerator::applyMergeProcess( @@ -829,7 +826,7 @@ AvoidLineArray ShiftLineGenerator::applyMergeProcess( // set parent id for (auto & al : merged_shift_lines) { - al.parent_ids = utils::avoidance::calcParentIds(shift_lines, al); + al.parent_ids = utils::static_obstacle_avoidance::calcParentIds(shift_lines, al); } // sort by distance from ego. @@ -937,7 +934,7 @@ void ShiftLineGenerator::applySmallShiftFilter( continue; } - if (s.start_longitudinal + 1e-3 < helper_->getMinimumPrepareDistance()) { + if (!helper_->isEnoughPrepareDistance(s.start_longitudinal)) { continue; } @@ -971,15 +968,15 @@ void ShiftLineGenerator::applySimilarGradFilter( for (size_t i = 1; i < input.size(); ++i) { AvoidLine combine{}; - utils::avoidance::setStartData( + utils::static_obstacle_avoidance::setStartData( combine, base_line.start_shift_length, base_line.start, base_line.start_idx, base_line.start_longitudinal); - utils::avoidance::setEndData( + utils::static_obstacle_avoidance::setEndData( combine, input.at(i).end_shift_length, input.at(i).end, input.at(i).end_idx, input.at(i).end_longitudinal); - combine.parent_ids = - utils::avoidance::concatParentIds(base_line.parent_ids, input.at(i).parent_ids); + combine.parent_ids = utils::static_obstacle_avoidance::concatParentIds( + base_line.parent_ids, input.at(i).parent_ids); combine_buffer.push_back(input.at(i)); @@ -1068,14 +1065,16 @@ AvoidLineArray ShiftLineGenerator::addReturnShiftLine( // avoidance points: No, shift points: Yes -> select last shift point. if (!has_candidate_point && has_registered_point) { - last_sl = utils::avoidance::fillAdditionalInfo(data, AvoidLine{last_.value()}); + last_sl = + utils::static_obstacle_avoidance::fillAdditionalInfo(data, AvoidLine{last_.value()}); } // avoidance points: Yes, shift points: Yes -> select the last one from both. if (has_candidate_point && has_registered_point) { helper_->alignShiftLinesOrder(ret, false); const auto & al = ret.back(); - const auto & sl = utils::avoidance::fillAdditionalInfo(data, AvoidLine{last_.value()}); + const auto & sl = + utils::static_obstacle_avoidance::fillAdditionalInfo(data, AvoidLine{last_.value()}); last_sl = (sl.end_longitudinal > al.end_longitudinal) ? sl : al; } @@ -1181,13 +1180,13 @@ AvoidLineArray ShiftLineGenerator::addReturnShiftLine( std::max(nominal_prepare_distance - last_sl_distance, 0.0); double prepare_distance_scaled = std::max( - helper_->getMinimumPrepareDistance(), std::max(nominal_prepare_distance, last_sl_distance)); + helper_->getNominalPrepareDistance(), std::max(nominal_prepare_distance, last_sl_distance)); double avoid_distance_scaled = nominal_avoid_distance; if (remaining_distance < prepare_distance_scaled + avoid_distance_scaled) { const auto scale = (remaining_distance - last_sl_distance) / std::max(nominal_avoid_distance + variable_prepare_distance, 0.1); prepare_distance_scaled = std::max( - helper_->getMinimumPrepareDistance(), last_sl_distance + scale * nominal_prepare_distance); + helper_->getNominalPrepareDistance(), last_sl_distance + scale * nominal_prepare_distance); avoid_distance_scaled *= scale; } @@ -1198,8 +1197,8 @@ AvoidLineArray ShiftLineGenerator::addReturnShiftLine( al.start_idx = last_sl.end_idx; al.start = last_sl.end; al.start_longitudinal = arclength_from_ego.at(al.start_idx); - al.end_idx = - utils::avoidance::findPathIndexFromArclength(arclength_from_ego, prepare_distance_scaled); + al.end_idx = utils::static_obstacle_avoidance::findPathIndexFromArclength( + arclength_from_ego, prepare_distance_scaled); al.end = data.reference_path.points.at(al.end_idx).point.pose; al.end_longitudinal = prepare_distance_scaled; al.end_shift_length = last_sl.end_shift_length; @@ -1212,11 +1211,11 @@ AvoidLineArray ShiftLineGenerator::addReturnShiftLine( { AvoidLine al; al.id = generateUUID(); - al.start_idx = - utils::avoidance::findPathIndexFromArclength(arclength_from_ego, prepare_distance_scaled); + al.start_idx = utils::static_obstacle_avoidance::findPathIndexFromArclength( + arclength_from_ego, prepare_distance_scaled); al.start = data.reference_path.points.at(al.start_idx).point.pose; al.start_longitudinal = prepare_distance_scaled; - al.end_idx = utils::avoidance::findPathIndexFromArclength( + al.end_idx = utils::static_obstacle_avoidance::findPathIndexFromArclength( arclength_from_ego, prepare_distance_scaled + avoid_distance_scaled); al.end = data.reference_path.points.at(al.end_idx).point.pose; al.end_longitudinal = arclength_from_ego.at(al.end_idx); @@ -1300,7 +1299,7 @@ AvoidLineArray ShiftLineGenerator::findNewShiftLine( const auto & candidate = shift_lines.at(i); // prevent sudden steering. - if (candidate.start_longitudinal + 1e-3 < helper_->getMinimumPrepareDistance()) { + if (!helper_->isEnoughPrepareDistance(candidate.start_longitudinal)) { break; } @@ -1323,7 +1322,7 @@ AvoidLineArray ShiftLineGenerator::findNewShiftLine( void ShiftLineGenerator::updateRegisteredRawShiftLines(const AvoidancePlanningData & data) { - utils::avoidance::fillAdditionalInfoFromPoint(data, raw_registered_); + utils::static_obstacle_avoidance::fillAdditionalInfoFromPoint(data, raw_registered_); AvoidLineArray avoid_lines; @@ -1372,7 +1371,7 @@ void ShiftLineGenerator::setRawRegisteredShiftLine( } auto future_with_info = shift_lines; - utils::avoidance::fillAdditionalInfoFromPoint(data, future_with_info); + utils::static_obstacle_avoidance::fillAdditionalInfoFromPoint(data, future_with_info); // sort by longitudinal std::sort(future_with_info.begin(), future_with_info.end(), [](auto a, auto b) { @@ -1413,4 +1412,4 @@ void ShiftLineGenerator::setRawRegisteredShiftLine( } } } -} // namespace behavior_path_planner::utils::avoidance +} // namespace behavior_path_planner::utils::static_obstacle_avoidance diff --git a/planning/behavior_path_avoidance_module/src/utils.cpp b/planning/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp similarity index 86% rename from planning/behavior_path_avoidance_module/src/utils.cpp rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index 33718ae16a038..660b8d228b6f2 100644 --- a/planning/behavior_path_avoidance_module/src/utils.cpp +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -14,20 +14,14 @@ #include "behavior_path_planner_common/utils/utils.hpp" -#include "behavior_path_avoidance_module/data_structs.hpp" -#include "behavior_path_avoidance_module/utils.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/data_structs.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/utils.hpp" #include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" #include "behavior_path_planner_common/utils/traffic_light_utils.hpp" -#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" #include -#include -#include - -#include -#include #include #include @@ -43,27 +37,12 @@ #include #include -namespace behavior_path_planner::utils::avoidance +namespace behavior_path_planner::utils::static_obstacle_avoidance { using autoware_perception_msgs::msg::TrafficSignalElement; using behavior_path_planner::utils::traffic_light::calcDistanceToRedTrafficLight; using behavior_path_planner::utils::traffic_light::getDistanceToNextTrafficLight; -using geometry_msgs::msg::TransformStamped; -using motion_utils::calcLongitudinalOffsetPoint; -using motion_utils::calcSignedArcLength; -using motion_utils::findNearestIndex; -using motion_utils::findNearestSegmentIndex; -using motion_utils::insertTargetPoint; -using tier4_autoware_utils::calcDistance2d; -using tier4_autoware_utils::calcLateralDeviation; -using tier4_autoware_utils::calcOffsetPose; -using tier4_autoware_utils::calcYawDeviation; -using tier4_autoware_utils::createQuaternionFromRPY; -using tier4_autoware_utils::getPose; -using tier4_autoware_utils::pose2transform; -using tier4_planning_msgs::msg::AvoidanceDebugFactor; -using tier4_planning_msgs::msg::AvoidanceDebugMsg; namespace { @@ -339,25 +318,55 @@ bool isWithinCrosswalk( bool isWithinIntersection( const ObjectData & object, const std::shared_ptr & route_handler) { - const std::string id = object.overhang_lanelet.attributeOr("intersection_area", "else"); - if (id == "else") { + const std::string area_id = object.overhang_lanelet.attributeOr("intersection_area", "else"); + if (area_id == "else") { + return false; + } + + const std::string location = object.overhang_lanelet.attributeOr("location", "else"); + if (location == "private") { return false; } const auto object_polygon = tier4_autoware_utils::toPolygon2d(object.object); - const auto polygon = route_handler->getLaneletMapPtr()->polygonLayer.get(std::atoi(id.c_str())); + const auto polygon = + route_handler->getLaneletMapPtr()->polygonLayer.get(std::atoi(area_id.c_str())); return boost::geometry::within( object_polygon, utils::toPolygon2d(lanelet::utils::to2D(polygon.basicPolygon()))); } -bool isOnEgoLane(const ObjectData & object) +bool isOnEgoLane(const ObjectData & object, const std::shared_ptr & route_handler) { const auto & object_pos = object.object.kinematics.initial_pose_with_covariance.pose.position; - return boost::geometry::within( - lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object_pos)).basicPoint(), - object.overhang_lanelet.polygon2d().basicPolygon()); + if (boost::geometry::within( + lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object_pos)).basicPoint(), + object.overhang_lanelet.polygon2d().basicPolygon())) { + return true; + } + + // push previous lanelet + lanelet::ConstLanelets prev_lanelet; + if (route_handler->getPreviousLaneletsWithinRoute(object.overhang_lanelet, &prev_lanelet)) { + if (boost::geometry::within( + lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object_pos)).basicPoint(), + prev_lanelet.front().polygon2d().basicPolygon())) { + return true; + } + } + + // push next lanelet + lanelet::ConstLanelet next_lanelet; + if (route_handler->getNextLaneletWithinRoute(object.overhang_lanelet, &next_lanelet)) { + if (boost::geometry::within( + lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(object_pos)).basicPoint(), + next_lanelet.polygon2d().basicPolygon())) { + return true; + } + } + + return false; } bool isParallelToEgoLane(const ObjectData & object, const double threshold) @@ -418,33 +427,41 @@ bool isParkedVehicle( bool is_left_side_parked_vehicle = false; if (!isOnRight(object)) { - auto [object_shiftable_distance, sub_type] = [&]() { - const auto most_left_road_lanelet = - route_handler->getMostLeftLanelet(object.overhang_lanelet); - const auto most_left_lanelet_candidates = - route_handler->getLaneletMapPtr()->laneletLayer.findUsages( - most_left_road_lanelet.leftBound()); - - lanelet::ConstLanelet most_left_lanelet = most_left_road_lanelet; - const lanelet::Attribute sub_type = - most_left_lanelet.attribute(lanelet::AttributeName::Subtype); - - for (const auto & ll : most_left_lanelet_candidates) { - const lanelet::Attribute sub_type = ll.attribute(lanelet::AttributeName::Subtype); - if (sub_type.value() == "road_shoulder") { - most_left_lanelet = ll; - } + const auto most_left_lanelet = [&]() { + auto same_direction_lane = + route_handler->getMostLeftLanelet(object.overhang_lanelet, true, true); + const lanelet::Attribute & sub_type = + same_direction_lane.attribute(lanelet::AttributeName::Subtype); + if (sub_type == "road_shoulder") { + return same_direction_lane; } - const auto center_to_left_boundary = distance2d( - to2D(most_left_lanelet.leftBound().basicLineString()), - to2D(toLaneletPoint(centerline_pos)).basicPoint()); + const auto opposite_lanes = route_handler->getLeftOppositeLanelets(same_direction_lane); + if (opposite_lanes.empty()) { + return same_direction_lane; + } - return std::make_pair( - center_to_left_boundary - 0.5 * object.object.shape.dimensions.y, sub_type); + return static_cast(opposite_lanes.front().invert()); }(); - if (sub_type.value() != "road_shoulder") { + const auto center_to_left_boundary = distance2d( + to2D(most_left_lanelet.leftBound().basicLineString()), + to2D(toLaneletPoint(centerline_pos)).basicPoint()); + + double object_shiftable_distance = + center_to_left_boundary - 0.5 * object.object.shape.dimensions.y; + + const lanelet::Attribute & sub_type = + most_left_lanelet.attribute(lanelet::AttributeName::Subtype); + if (sub_type == "road_shoulder") { + // assuming it's parked vehicle if its CoG is within road shoulder lanelet. + if (boost::geometry::within( + to2D(toLaneletPoint(object_pos)).basicPoint(), + most_left_lanelet.polygon2d().basicPolygon())) { + return true; + } + } else { + // assuming there is 0.5m road shoulder even if it's not defined explicitly in HDMap. object_shiftable_distance += parameters->object_check_min_road_shoulder_width; } @@ -458,33 +475,41 @@ bool isParkedVehicle( bool is_right_side_parked_vehicle = false; if (isOnRight(object)) { - auto [object_shiftable_distance, sub_type] = [&]() { - const auto most_right_road_lanelet = - route_handler->getMostRightLanelet(object.overhang_lanelet); - const auto most_right_lanelet_candidates = - route_handler->getLaneletMapPtr()->laneletLayer.findUsages( - most_right_road_lanelet.rightBound()); - - lanelet::ConstLanelet most_right_lanelet = most_right_road_lanelet; - const lanelet::Attribute sub_type = - most_right_lanelet.attribute(lanelet::AttributeName::Subtype); - - for (const auto & ll : most_right_lanelet_candidates) { - const lanelet::Attribute sub_type = ll.attribute(lanelet::AttributeName::Subtype); - if (sub_type.value() == "road_shoulder") { - most_right_lanelet = ll; - } + const auto most_right_lanelet = [&]() { + auto same_direction_lane = + route_handler->getMostRightLanelet(object.overhang_lanelet, true, true); + const lanelet::Attribute & sub_type = + same_direction_lane.attribute(lanelet::AttributeName::Subtype); + if (sub_type == "road_shoulder") { + return same_direction_lane; } - const auto center_to_right_boundary = distance2d( - to2D(most_right_lanelet.rightBound().basicLineString()), - to2D(toLaneletPoint(centerline_pos)).basicPoint()); + const auto opposite_lanes = route_handler->getRightOppositeLanelets(same_direction_lane); + if (opposite_lanes.empty()) { + return same_direction_lane; + } - return std::make_pair( - center_to_right_boundary - 0.5 * object.object.shape.dimensions.y, sub_type); + return static_cast(opposite_lanes.front().invert()); }(); - if (sub_type.value() != "road_shoulder") { + const auto center_to_right_boundary = distance2d( + to2D(most_right_lanelet.rightBound().basicLineString()), + to2D(toLaneletPoint(centerline_pos)).basicPoint()); + + double object_shiftable_distance = + center_to_right_boundary - 0.5 * object.object.shape.dimensions.y; + + const lanelet::Attribute & sub_type = + most_right_lanelet.attribute(lanelet::AttributeName::Subtype); + if (sub_type == "road_shoulder") { + // assuming it's parked vehicle if its CoG is within road shoulder lanelet. + if (boost::geometry::within( + to2D(toLaneletPoint(object_pos)).basicPoint(), + most_right_lanelet.polygon2d().basicPolygon())) { + return true; + } + } else { + // assuming there is 0.5m road shoulder even if it's not defined explicitly in HDMap. object_shiftable_distance += parameters->object_check_min_road_shoulder_width; } @@ -551,47 +576,113 @@ bool isNeverAvoidanceTarget( const std::shared_ptr & planner_data, const std::shared_ptr & parameters) { - const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose; - const auto is_moving_distance_longer_than_threshold = - tier4_autoware_utils::calcDistance2d(object.init_pose, object_pose) > - parameters->distance_threshold_for_ambiguous_vehicle; - if (is_moving_distance_longer_than_threshold) { - object.reason = AvoidanceDebugFactor::MOVING_OBJECT; - return true; - } - if (object.is_within_intersection) { if (object.behavior == ObjectData::Behavior::NONE) { - object.reason = "ParallelToEgoLane"; + object.info = ObjectInfo::PARALLEL_TO_EGO_LANE; 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"; + object.info = ObjectInfo::MERGING_TO_EGO_LANE; RCLCPP_DEBUG( rclcpp::get_logger(logger_namespace), "object belongs to ego lane. never avoid it."); return true; } } + if (object.behavior == ObjectData::Behavior::MERGING) { + object.info = ObjectInfo::MERGING_TO_EGO_LANE; + if ( + isOnRight(object) && !object.is_parked && + object.overhang_points.front().first > parameters->th_overhang_distance) { + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), + "merging vehicle. but overhang distance is larger than threshold."); + return true; + } + if ( + !isOnRight(object) && !object.is_parked && + object.overhang_points.front().first < -1.0 * parameters->th_overhang_distance) { + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), + "merging vehicle. but overhang distance is larger than threshold."); + return true; + } + } + + if (object.behavior == ObjectData::Behavior::DEVIATING) { + object.info = ObjectInfo::DEVIATING_FROM_EGO_LANE; + if ( + isOnRight(object) && !object.is_parked && + object.overhang_points.front().first > parameters->th_overhang_distance) { + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), + "deviating vehicle. but overhang distance is larger than threshold."); + return true; + } + if ( + !isOnRight(object) && !object.is_parked && + object.overhang_points.front().first < -1.0 * parameters->th_overhang_distance) { + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), + "deviating vehicle. but overhang distance is larger than threshold."); + return true; + } + } + if (object.is_on_ego_lane) { const auto right_lane = - planner_data->route_handler->getRightLanelet(object.overhang_lanelet, true, false); + planner_data->route_handler->getRightLanelet(object.overhang_lanelet, true, true); + if (right_lane.has_value() && isOnRight(object)) { + const lanelet::Attribute & right_lane_sub_type = + right_lane.value().attribute(lanelet::AttributeName::Subtype); + if (right_lane_sub_type != "road_shoulder") { + object.info = ObjectInfo::IS_NOT_PARKING_OBJECT; + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), "object isn't on the edge lane. never avoid it."); + return true; + } + + const auto object_polygon = tier4_autoware_utils::toPolygon2d(object.object); + const auto is_disjoint_right_lane = + boost::geometry::disjoint(object_polygon, right_lane.value().polygon2d().basicPolygon()); + if (is_disjoint_right_lane) { + object.info = ObjectInfo::IS_NOT_PARKING_OBJECT; + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), "object isn't on the edge lane. never avoid it."); + return true; + } + } + 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(logger_namespace), "object isn't on the edge lane. never avoid it."); - return true; + planner_data->route_handler->getLeftLanelet(object.overhang_lanelet, true, true); + if (left_lane.has_value() && !isOnRight(object)) { + const lanelet::Attribute & left_lane_sub_type = + left_lane.value().attribute(lanelet::AttributeName::Subtype); + if (left_lane_sub_type != "road_shoulder") { + object.info = ObjectInfo::IS_NOT_PARKING_OBJECT; + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), "object isn't on the edge lane. never avoid it."); + return true; + } + + const auto object_polygon = tier4_autoware_utils::toPolygon2d(object.object); + const auto is_disjoint_left_lane = + boost::geometry::disjoint(object_polygon, left_lane.value().polygon2d().basicPolygon()); + if (is_disjoint_left_lane) { + object.info = ObjectInfo::IS_NOT_PARKING_OBJECT; + RCLCPP_DEBUG( + rclcpp::get_logger(logger_namespace), "object isn't on the edge lane. never avoid it."); + return true; + } } } if (isCloseToStopFactor(object, data, planner_data, parameters)) { if (object.is_on_ego_lane && !object.is_parked) { - object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT; + object.info = ObjectInfo::IS_NOT_PARKING_OBJECT; RCLCPP_DEBUG( rclcpp::get_logger(logger_namespace), "object is close to stop factor. never avoid it."); return true; @@ -619,11 +710,11 @@ bool isObviousAvoidanceTarget( } if (!object.is_parked) { - object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT; + object.info = ObjectInfo::IS_NOT_PARKING_OBJECT; } if (object.behavior == ObjectData::Behavior::MERGING) { - object.reason = "MergingToEgoLane"; + object.info = ObjectInfo::MERGING_TO_EGO_LANE; } return false; @@ -636,13 +727,13 @@ bool isSatisfiedWithCommonCondition( { // Step1. filtered by target object type. if (!isAvoidanceTargetObjectType(object.object, parameters)) { - object.reason = AvoidanceDebugFactor::OBJECT_IS_NOT_TYPE; + object.info = ObjectInfo::IS_NOT_TARGET_OBJECT; return false; } // Step2. filtered stopped objects. if (filtering_utils::isMovingObject(object, parameters)) { - object.reason = AvoidanceDebugFactor::MOVING_OBJECT; + object.info = ObjectInfo::MOVING_OBJECT; return false; } @@ -651,12 +742,12 @@ bool isSatisfiedWithCommonCondition( fillLongitudinalAndLengthByClosestEnvelopeFootprint(data.reference_path_rough, ego_pos, object); if (object.longitudinal < -parameters->object_check_backward_distance) { - object.reason = AvoidanceDebugFactor::OBJECT_IS_BEHIND_THRESHOLD; + object.info = ObjectInfo::FURTHER_THAN_THRESHOLD; return false; } if (object.longitudinal > forward_detection_range) { - object.reason = AvoidanceDebugFactor::OBJECT_IS_IN_FRONT_THRESHOLD; + object.info = ObjectInfo::FURTHER_THAN_THRESHOLD; return false; } @@ -667,12 +758,12 @@ bool isSatisfiedWithCommonCondition( const auto ego_idx = planner_data->findEgoIndex(data.reference_path_rough.points); const auto to_goal_distance = rh->isInGoalRouteSection(data.current_lanelets.back()) - ? calcSignedArcLength( + ? motion_utils::calcSignedArcLength( data.reference_path_rough.points, ego_idx, data.reference_path_rough.points.size() - 1) : std::numeric_limits::max(); if (object.longitudinal > to_goal_distance) { - object.reason = AvoidanceDebugFactor::OBJECT_BEHIND_PATH_GOAL; + object.info = ObjectInfo::FURTHER_THAN_GOAL; return false; } @@ -680,7 +771,7 @@ bool isSatisfiedWithCommonCondition( if ( object.longitudinal + object.length / 2 + parameters->object_check_goal_distance > to_goal_distance) { - object.reason = "TooNearToGoal"; + object.info = ObjectInfo::TOO_NEAR_TO_GOAL; return false; } } @@ -695,7 +786,7 @@ bool isSatisfiedWithNonVehicleCondition( { // avoidance module ignore pedestrian and bicycle around crosswalk if (isWithinCrosswalk(object, planner_data->route_handler->getOverallGraphPtr())) { - object.reason = "CrosswalkUser"; + object.info = ObjectInfo::CROSSWALK_USER; return false; } @@ -704,7 +795,7 @@ bool isSatisfiedWithNonVehicleCondition( object.to_centerline = lanelet::utils::getArcCoordinates(data.current_lanelets, object_pose).distance; if (std::abs(object.to_centerline) < parameters->threshold_distance_object_is_on_center) { - object.reason = AvoidanceDebugFactor::TOO_NEAR_TO_CENTERLINE; + object.info = ObjectInfo::TOO_NEAR_TO_CENTERLINE; return false; } @@ -728,7 +819,7 @@ bool isSatisfiedWithVehicleCondition( const std::shared_ptr & parameters) { object.behavior = getObjectBehavior(object, parameters); - object.is_on_ego_lane = isOnEgoLane(object); + object.is_on_ego_lane = isOnEgoLane(object, planner_data->route_handler); if (isNeverAvoidanceTarget(object, data, planner_data, parameters)) { return false; @@ -741,32 +832,41 @@ bool isSatisfiedWithVehicleCondition( // from here, filtering for ambiguous vehicle. if (!parameters->enable_avoidance_for_ambiguous_vehicle) { - object.reason = "AmbiguousStoppedVehicle"; + object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE; return false; } const auto stop_time_longer_than_threshold = object.stop_time > parameters->time_threshold_for_ambiguous_vehicle; if (!stop_time_longer_than_threshold) { - object.reason = "AmbiguousStoppedVehicle(wait-and-see)"; + object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE; + return false; + } + + const auto & current_pose = object.object.kinematics.initial_pose_with_covariance.pose; + const auto is_moving_distance_longer_than_threshold = + calcDistance2d(object.init_pose, current_pose) > + parameters->distance_threshold_for_ambiguous_vehicle; + if (is_moving_distance_longer_than_threshold) { + object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE; return false; } if (object.is_within_intersection) { if (object.behavior == ObjectData::Behavior::DEVIATING) { - object.reason = "AmbiguousStoppedVehicle(wait-and-see)"; + object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE; object.is_ambiguous = true; return true; } } else { if (object.behavior == ObjectData::Behavior::MERGING) { - object.reason = "AmbiguousStoppedVehicle(wait-and-see)"; + object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE; object.is_ambiguous = true; return true; } if (object.behavior == ObjectData::Behavior::DEVIATING) { - object.reason = "AmbiguousStoppedVehicle(wait-and-see)"; + object.info = ObjectInfo::AMBIGUOUS_STOPPED_VEHICLE; object.is_ambiguous = true; return true; } @@ -777,7 +877,7 @@ bool isSatisfiedWithVehicleCondition( } } - object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT; + object.info = ObjectInfo::IS_NOT_PARKING_OBJECT; return false; } @@ -791,12 +891,12 @@ bool isNoNeedAvoidanceBehavior( const auto shift_length = calcShiftLength( isOnRight(object), object.overhang_points.front().first, object.avoid_margin.value()); if (!isShiftNecessary(isOnRight(object), shift_length)) { - object.reason = "NotNeedAvoidance"; + object.info = ObjectInfo::ENOUGH_LATERAL_DISTANCE; return true; } if (std::abs(shift_length) < parameters->lateral_execution_threshold) { - object.reason = "LessThanExecutionThreshold"; + object.info = ObjectInfo::LESS_THAN_EXECUTION_THRESHOLD; return true; } @@ -845,7 +945,7 @@ double getRoadShoulderDistance( const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose; const auto object_closest_index = - findNearestIndex(data.reference_path.points, object_pose.position); + motion_utils::findNearestIndex(data.reference_path.points, object_pose.position); const auto object_closest_pose = data.reference_path.points.at(object_closest_index).point.pose; const auto rh = planner_data->route_handler; @@ -877,8 +977,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)); @@ -1088,7 +1194,7 @@ void fillLongitudinalAndLengthByClosestEnvelopeFootprint( for (const auto & p : obj.envelope_poly.outer()) { const auto point = tier4_autoware_utils::createPoint(p.x(), p.y(), 0.0); // TODO(someone): search around first position where the ego should avoid the object. - const double arc_length = calcSignedArcLength(path.points, ego_pos, point); + const double arc_length = motion_utils::calcSignedArcLength(path.points, ego_pos, point); min_distance = std::min(min_distance, arc_length); max_distance = std::max(max_distance, arc_length); } @@ -1105,7 +1211,7 @@ std::vector> calcEnvelopeOverhangDistance( for (const auto & p : object_data.envelope_poly.outer()) { const auto point = tier4_autoware_utils::createPoint(p.x(), p.y(), 0.0); // TODO(someone): search around first position where the ego should avoid the object. - const auto idx = findNearestIndex(path.points, point); + const auto idx = motion_utils::findNearestIndex(path.points, point); const auto lateral = calcLateralDeviation(getPose(path.points.at(idx)), point); overhang_points.emplace_back(lateral, point); } @@ -1276,15 +1382,16 @@ void insertDecelPoint( const Point & p_src, const double offset, const double velocity, PathWithLaneId & path, std::optional & p_out) { - const auto decel_point = calcLongitudinalOffsetPoint(path.points, p_src, offset); + const auto decel_point = motion_utils::calcLongitudinalOffsetPoint(path.points, p_src, offset); if (!decel_point) { // TODO(Satoshi OTA) Think later the process in the case of no decel point found. return; } - const auto seg_idx = findNearestSegmentIndex(path.points, decel_point.value()); - const auto insert_idx = insertTargetPoint(seg_idx, decel_point.value(), path.points); + const auto seg_idx = motion_utils::findNearestSegmentIndex(path.points, decel_point.value()); + const auto insert_idx = + motion_utils::insertTargetPoint(seg_idx, decel_point.value(), path.points); if (!insert_idx) { // TODO(Satoshi OTA) Think later the process in the case of no decel point found. @@ -1384,6 +1491,7 @@ void fillObjectMovingTime( object_data.last_stop = now; object_data.move_time = 0.0; if (is_new_object) { + object_data.init_pose = object_data.object.kinematics.initial_pose_with_covariance.pose; object_data.stop_time = 0.0; object_data.last_move = now; stopped_objects.push_back(object_data); @@ -1392,11 +1500,13 @@ void fillObjectMovingTime( same_id_obj->last_stop = now; same_id_obj->move_time = 0.0; object_data.stop_time = same_id_obj->stop_time; + object_data.init_pose = same_id_obj->init_pose; } return; } if (is_new_object) { + object_data.init_pose = object_data.object.kinematics.initial_pose_with_covariance.pose; object_data.move_time = std::numeric_limits::infinity(); object_data.stop_time = 0.0; object_data.last_move = now; @@ -1406,6 +1516,7 @@ void fillObjectMovingTime( object_data.last_stop = same_id_obj->last_stop; object_data.move_time = (now - same_id_obj->last_stop).seconds(); object_data.stop_time = 0.0; + object_data.init_pose = object_data.object.kinematics.initial_pose_with_covariance.pose; if (object_data.move_time > object_parameter.moving_time_threshold) { stopped_objects.erase(same_id_obj); @@ -1452,22 +1563,6 @@ void fillAvoidanceNecessity( object_data.avoid_required = check_necessity(parameters->hysteresis_factor_expand_rate); } -void fillInitialPose(ObjectData & object_data, ObjectDataArray & detected_objects) -{ - const auto id = object_data.object.object_id; - const auto same_id_obj = std::find_if( - detected_objects.begin(), detected_objects.end(), - [&id](const auto & o) { return o.object.object_id == id; }); - - if (same_id_obj != detected_objects.end()) { - object_data.init_pose = same_id_obj->init_pose; - return; - } - - object_data.init_pose = object_data.object.kinematics.initial_pose_with_covariance.pose; - detected_objects.push_back(object_data); -} - void fillObjectStoppableJudge( ObjectData & object_data, const ObjectDataArray & registered_objects, const double feasible_stop_distance, const std::shared_ptr & parameters) @@ -1651,14 +1746,15 @@ void filterTargetObjects( } // Find the footprint point closest to the path, set to object_data.overhang_distance. - o.overhang_points = utils::avoidance::calcEnvelopeOverhangDistance(o, data.reference_path); + o.overhang_points = + utils::static_obstacle_avoidance::calcEnvelopeOverhangDistance(o, data.reference_path); o.to_road_shoulder_distance = filtering_utils::getRoadShoulderDistance(o, data, planner_data); // TODO(Satoshi Ota) parametrize stop time threshold if need. constexpr double STOP_TIME_THRESHOLD = 3.0; // [s] if (filtering_utils::isUnknownTypeObject(o)) { if (o.stop_time < STOP_TIME_THRESHOLD) { - o.reason = "UnstableObject"; + o.info = ObjectInfo::UNSTABLE_OBJECT; data.other_objects.push_back(o); continue; } @@ -1717,9 +1813,9 @@ void fillAdditionalInfoFromPoint(const AvoidancePlanningData & data, AvoidLineAr // calc longitudinal for (auto & sl : lines) { - sl.start_idx = findNearestIndex(path.points, sl.start.position); + sl.start_idx = motion_utils::findNearestIndex(path.points, sl.start.position); sl.start_longitudinal = arc.at(sl.start_idx); - sl.end_idx = findNearestIndex(path.points, sl.end.position); + sl.end_idx = motion_utils::findNearestIndex(path.points, sl.end.position); sl.end_longitudinal = arc.at(sl.end_idx); } } @@ -1886,7 +1982,7 @@ std::vector getSafetyCheckTargetObjects( std::for_each(objects.begin(), objects.end(), [&p, &ret, ¶meters](const auto & object) { if (filtering_utils::isSafetyCheckTargetObjectType(object.object, parameters)) { // check only moving objects - if (filtering_utils::isMovingObject(object, parameters)) { + if (filtering_utils::isMovingObject(object, parameters) || !object.is_parked) { ret.objects.push_back(object.object); } } @@ -2016,7 +2112,8 @@ std::pair separateObjectsByPath( Pose p_spline_ego_front = spline_path.points.front().point.pose; double next_longitudinal_distance = parameters->resample_interval_for_output; for (size_t i = 0; i < points_size; ++i) { - const auto distance_from_ego = calcSignedArcLength(reference_path.points, ego_idx, i); + const auto distance_from_ego = + motion_utils::calcSignedArcLength(reference_path.points, ego_idx, i); if (distance_from_ego > object_check_forward_distance) { break; } @@ -2190,7 +2287,7 @@ DrivableLanes generateExpandedDrivableLanes( break; } if (i == max_recursive_search_num - 1) { - RCLCPP_ERROR( + RCLCPP_DEBUG( rclcpp::get_logger(logger_namespace), "Drivable area expansion reaches max iteration."); } } @@ -2264,7 +2361,7 @@ double calcDistanceToReturnDeadLine( if (planner_data->route_handler->isInGoalRouteSection(lanelets.back())) { const auto & ego_pos = planner_data->self_odometry->pose.pose.position; const auto to_goal_distance = - calcSignedArcLength(path.points, ego_pos, path.points.size() - 1); + motion_utils::calcSignedArcLength(path.points, ego_pos, path.points.size() - 1); distance_to_return_dead_line = std::min( distance_to_return_dead_line, to_goal_distance - parameters->dead_line_buffer_for_goal); } @@ -2272,4 +2369,4 @@ double calcDistanceToReturnDeadLine( return distance_to_return_dead_line; } -} // namespace behavior_path_planner::utils::avoidance +} // namespace behavior_path_planner::utils::static_obstacle_avoidance diff --git a/planning/behavior_path_dynamic_avoidance_module/test/test_behavior_path_planner_node_interface.cpp b/planning/autoware_behavior_path_static_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp similarity index 81% rename from planning/behavior_path_dynamic_avoidance_module/test/test_behavior_path_planner_node_interface.cpp rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp index 16b4ffbc688ae..c70b78265a17b 100644 --- a/planning/behavior_path_dynamic_avoidance_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/autoware_behavior_path_static_obstacle_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 @@ -47,22 +47,22 @@ std::shared_ptr generateNode() ament_index_cpp::get_package_share_directory("behavior_path_planner"); std::vector module_names; - module_names.emplace_back("behavior_path_planner::DynamicAvoidanceModuleManager"); + module_names.emplace_back("behavior_path_planner::StaticObstacleAvoidanceModuleManager"); std::vector params; params.emplace_back("launch_modules", module_names); node_options.parameter_overrides(params); test_utils::updateNodeOptions( - node_options, - {planning_test_utils_dir + "/config/test_common.param.yaml", - planning_test_utils_dir + "/config/test_nearest_search.param.yaml", - planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", - behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", - behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", - behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", - ament_index_cpp::get_package_share_directory("behavior_path_dynamic_avoidance_module") + - "/config/dynamic_avoidance.param.yaml"}); + node_options, {planning_test_utils_dir + "/config/test_common.param.yaml", + planning_test_utils_dir + "/config/test_nearest_search.param.yaml", + planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + behavior_path_planner_dir + "/config/behavior_path_planner.param.yaml", + behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", + behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", + ament_index_cpp::get_package_share_directory( + "autoware_behavior_path_static_obstacle_avoidance_module") + + "/config/static_obstacle_avoidance.param.yaml"}); return std::make_shared(node_options); } diff --git a/planning/behavior_path_avoidance_module/test/test_utils.cpp b/planning/autoware_behavior_path_static_obstacle_avoidance_module/test/test_utils.cpp similarity index 56% rename from planning/behavior_path_avoidance_module/test/test_utils.cpp rename to planning/autoware_behavior_path_static_obstacle_avoidance_module/test/test_utils.cpp index 95488daa69cf8..da681e72533b0 100644 --- a/planning/behavior_path_avoidance_module/test/test_utils.cpp +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/test/test_utils.cpp @@ -12,15 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "behavior_path_avoidance_module/data_structs.hpp" -#include "behavior_path_avoidance_module/utils.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/data_structs.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/utils.hpp" #include #include using behavior_path_planner::ObjectData; -using behavior_path_planner::utils::avoidance::isOnRight; -using behavior_path_planner::utils::avoidance::isSameDirectionShift; +using behavior_path_planner::utils::static_obstacle_avoidance::isOnRight; +using behavior_path_planner::utils::static_obstacle_avoidance::isSameDirectionShift; +using behavior_path_planner::utils::static_obstacle_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)); +} diff --git a/planning/behavior_velocity_planner/CMakeLists.txt b/planning/autoware_behavior_velocity_planner/CMakeLists.txt similarity index 90% rename from planning/behavior_velocity_planner/CMakeLists.txt rename to planning/autoware_behavior_velocity_planner/CMakeLists.txt index ee7dd7c07a77a..37a02b844dfe9 100644 --- a/planning/behavior_velocity_planner/CMakeLists.txt +++ b/planning/autoware_behavior_velocity_planner/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(behavior_velocity_planner) +project(autoware_behavior_velocity_planner) find_package(autoware_cmake REQUIRED) find_package(rosidl_default_generators REQUIRED) @@ -19,7 +19,7 @@ ament_auto_add_library(${PROJECT_NAME}_lib SHARED ) rclcpp_components_register_node(${PROJECT_NAME}_lib - PLUGIN "behavior_velocity_planner::BehaviorVelocityPlannerNode" + PLUGIN "autoware::behavior_velocity_planner::BehaviorVelocityPlannerNode" EXECUTABLE ${PROJECT_NAME}_node ) diff --git a/planning/behavior_velocity_planner/README.md b/planning/autoware_behavior_velocity_planner/README.md similarity index 62% rename from planning/behavior_velocity_planner/README.md rename to planning/autoware_behavior_velocity_planner/README.md index 519e68764b450..a68705e3f73a2 100644 --- a/planning/behavior_velocity_planner/README.md +++ b/planning/autoware_behavior_velocity_planner/README.md @@ -56,3 +56,15 @@ So for example, in order to stop at a stop line with the vehicles' front on the | `max_accel` | double | (to be a global parameter) max acceleration of the vehicle | | `system_delay` | double | (to be a global parameter) delay time until output control command | | `delay_response_time` | double | (to be a global parameter) delay time of the vehicle's response to control commands | + +## Traffic Light Handling in sim/real + +The handling of traffic light information varies depending on the usage. In the below table, the traffic signal topic element for the corresponding lane is denoted as `info`, and if `info` is not available, it is denoted as `null`. + +| module \\ case | `info` is `null` | `info` is not `null` | +| :--------------------------------------------------------------------------------------------------------- | ------------------------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | +| intersection_occlusion(`is_simulation = *`)
  • `info` is the latest non-`null` information
| GO(occlusion is ignored) | intersection_occlusion uses the latest non UNKNOWN observation in the queue up to present.
  • If `info` is `GREEN or UNKNOWN`, occlusion is cared
  • If `info` is `RED or YELLOW`, occlusion is ignored(GO)
  • NOTE: Currently timeout is not considered
| +| traffic_light(sim, `is_simulation = true`)
  • `info` is current information
| GO | traffic_light uses the perceived traffic light information at present directly.
  • If `info` is timeout, STOP whatever the color is
  • If `info` is not timeout, then act according to the color. If `info` is `UNKNOWN`, STOP
{: rowspan=2} | +| traffic_light(real, `is_simulation = false`)
  • `info` is current information
| STOP | ⁠ {: style="padding:0"} | +| crosswalk with Traffic Light(`is_simulation = *`)
  • `info` is current information
| default |
  • If `disable_yield_for_new_stopped_object` is true, each sub scene_module ignore newly detected pedestrians after module instantiation.
  • If `ignore_with_traffic_light` is true, occlusion detection is skipped.
| +| map_based_prediction(`is_simulation = *`)
  • `info` is current information
| default | If a pedestrian traffic light is
  • RED, surrounding pedestrians are not predicted.
  • GREEN, stopped pedestrians are not predicted.
| diff --git a/planning/behavior_velocity_planner/config/behavior_velocity_planner.param.yaml b/planning/autoware_behavior_velocity_planner/config/behavior_velocity_planner.param.yaml similarity index 100% rename from planning/behavior_velocity_planner/config/behavior_velocity_planner.param.yaml rename to planning/autoware_behavior_velocity_planner/config/behavior_velocity_planner.param.yaml diff --git a/planning/behavior_velocity_planner/docs/BehaviorVelocityPlanner-Architecture.drawio.svg b/planning/autoware_behavior_velocity_planner/docs/BehaviorVelocityPlanner-Architecture.drawio.svg similarity index 100% rename from planning/behavior_velocity_planner/docs/BehaviorVelocityPlanner-Architecture.drawio.svg rename to planning/autoware_behavior_velocity_planner/docs/BehaviorVelocityPlanner-Architecture.drawio.svg diff --git a/planning/behavior_velocity_planner/docs/set_stop_velocity.drawio.svg b/planning/autoware_behavior_velocity_planner/docs/set_stop_velocity.drawio.svg similarity index 100% rename from planning/behavior_velocity_planner/docs/set_stop_velocity.drawio.svg rename to planning/autoware_behavior_velocity_planner/docs/set_stop_velocity.drawio.svg diff --git a/planning/behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml b/planning/autoware_behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml similarity index 97% rename from planning/behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml rename to planning/autoware_behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml index c1631fdb739de..d4478f87f0610 100644 --- a/planning/behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml +++ b/planning/autoware_behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml @@ -30,7 +30,7 @@ - + diff --git a/planning/behavior_velocity_planner/package.xml b/planning/autoware_behavior_velocity_planner/package.xml similarity index 96% rename from planning/behavior_velocity_planner/package.xml rename to planning/autoware_behavior_velocity_planner/package.xml index 1357b555f0ba4..573d862f1725b 100644 --- a/planning/behavior_velocity_planner/package.xml +++ b/planning/autoware_behavior_velocity_planner/package.xml @@ -1,9 +1,9 @@ - behavior_velocity_planner + autoware_behavior_velocity_planner 0.1.0 - The behavior_velocity_planner package + The autoware_behavior_velocity_planner package Mamoru Sobue Takayuki Murooka diff --git a/planning/behavior_velocity_planner/schema/behavior_velocity_planner.schema.json b/planning/autoware_behavior_velocity_planner/schema/behavior_velocity_planner.schema.json similarity index 100% rename from planning/behavior_velocity_planner/schema/behavior_velocity_planner.schema.json rename to planning/autoware_behavior_velocity_planner/schema/behavior_velocity_planner.schema.json diff --git a/planning/behavior_velocity_planner/src/node.cpp b/planning/autoware_behavior_velocity_planner/src/node.cpp similarity index 95% rename from planning/behavior_velocity_planner/src/node.cpp rename to planning/autoware_behavior_velocity_planner/src/node.cpp index aa9613a35dd7c..d4ae3897bca65 100644 --- a/planning/behavior_velocity_planner/src/node.cpp +++ b/planning/autoware_behavior_velocity_planner/src/node.cpp @@ -52,7 +52,7 @@ rclcpp::SubscriptionOptions createSubscriptionOptions(rclcpp::Node * node_ptr) } } // namespace -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace { @@ -311,6 +311,7 @@ void BehaviorVelocityPlannerNode::onParam() // lock(mutex_); planner_data_.velocity_smoother_ = std::make_unique(*this); + planner_data_.velocity_smoother_->setWheelBase(planner_data_.vehicle_info_.wheel_base_m); } void BehaviorVelocityPlannerNode::onLaneletMap( @@ -352,6 +353,7 @@ void BehaviorVelocityPlannerNode::onTrafficSignals( planner_data_.traffic_light_id_map_last_observed_[signal.traffic_signal_id].stamp = msg->stamp; } else { + // if (1)the observation is not UNKNOWN or (2)the very first observation is UNKNOWN planner_data_.traffic_light_id_map_last_observed_[signal.traffic_signal_id] = traffic_signal; } } @@ -434,14 +436,15 @@ autoware_auto_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generatePath std::make_shared(planner_data), *input_path_msg); // screening - const auto filtered_path = filterLitterPathPoint(to_path(velocity_planned_path)); + const auto filtered_path = + ::behavior_velocity_planner::filterLitterPathPoint(to_path(velocity_planned_path)); // interpolation - const auto interpolated_path_msg = - interpolatePath(filtered_path, forward_path_length_, behavior_output_path_interval_); + const auto interpolated_path_msg = ::behavior_velocity_planner::interpolatePath( + filtered_path, forward_path_length_, behavior_output_path_interval_); // check stop point - output_path_msg = filterStopPathPoint(interpolated_path_msg); + output_path_msg = ::behavior_velocity_planner::filterStopPathPoint(interpolated_path_msg); output_path_msg.header.frame_id = "map"; output_path_msg.header.stamp = this->now(); @@ -475,7 +478,7 @@ void BehaviorVelocityPlannerNode::publishDebugMarker( } debug_viz_pub_->publish(output_msg); } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #include -RCLCPP_COMPONENTS_REGISTER_NODE(behavior_velocity_planner::BehaviorVelocityPlannerNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::behavior_velocity_planner::BehaviorVelocityPlannerNode) diff --git a/planning/behavior_velocity_planner/src/node.hpp b/planning/autoware_behavior_velocity_planner/src/node.hpp similarity index 93% rename from planning/behavior_velocity_planner/src/node.hpp rename to planning/autoware_behavior_velocity_planner/src/node.hpp index dd6edf6ae0bc0..6e74203460542 100644 --- a/planning/behavior_velocity_planner/src/node.hpp +++ b/planning/autoware_behavior_velocity_planner/src/node.hpp @@ -18,8 +18,8 @@ #include "planner_manager.hpp" #include "tier4_autoware_utils/ros/logger_level_configure.hpp" -#include -#include +#include +#include #include #include #include @@ -44,11 +44,12 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { using autoware_auto_mapping_msgs::msg::HADMapBin; -using behavior_velocity_planner::srv::LoadPlugin; -using behavior_velocity_planner::srv::UnloadPlugin; +using autoware_behavior_velocity_planner::srv::LoadPlugin; +using autoware_behavior_velocity_planner::srv::UnloadPlugin; +using ::behavior_velocity_planner::TrafficSignalStamped; using tier4_planning_msgs::msg::VelocityLimit; class BehaviorVelocityPlannerNode : public rclcpp::Node @@ -134,6 +135,6 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node std::unique_ptr published_time_publisher_; }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // NODE_HPP_ diff --git a/planning/behavior_velocity_planner/src/planner_manager.cpp b/planning/autoware_behavior_velocity_planner/src/planner_manager.cpp similarity index 95% rename from planning/behavior_velocity_planner/src/planner_manager.cpp rename to planning/autoware_behavior_velocity_planner/src/planner_manager.cpp index cb491920c87d4..f939f67a06f9e 100644 --- a/planning/behavior_velocity_planner/src/planner_manager.cpp +++ b/planning/autoware_behavior_velocity_planner/src/planner_manager.cpp @@ -19,7 +19,7 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { namespace { @@ -50,7 +50,7 @@ diagnostic_msgs::msg::DiagnosticStatus makeStopReasonDiag( } // namespace BehaviorVelocityPlannerManager::BehaviorVelocityPlannerManager() -: plugin_loader_("behavior_velocity_planner", "behavior_velocity_planner::PluginInterface") +: plugin_loader_("autoware_behavior_velocity_planner", "behavior_velocity_planner::PluginInterface") { } @@ -128,4 +128,4 @@ diagnostic_msgs::msg::DiagnosticStatus BehaviorVelocityPlannerManager::getStopRe { return stop_reason_diag_; } -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/src/planner_manager.hpp b/planning/autoware_behavior_velocity_planner/src/planner_manager.hpp similarity index 91% rename from planning/behavior_velocity_planner/src/planner_manager.hpp rename to planning/autoware_behavior_velocity_planner/src/planner_manager.hpp index 7485e5faba8bf..f9c1d0253de62 100644 --- a/planning/behavior_velocity_planner/src/planner_manager.hpp +++ b/planning/autoware_behavior_velocity_planner/src/planner_manager.hpp @@ -36,8 +36,11 @@ #include #include -namespace behavior_velocity_planner +namespace autoware::behavior_velocity_planner { +using ::behavior_velocity_planner::PlannerData; +using ::behavior_velocity_planner::PluginInterface; + class BehaviorVelocityPlannerManager { public: @@ -56,6 +59,6 @@ class BehaviorVelocityPlannerManager pluginlib::ClassLoader plugin_loader_; std::vector> scene_manager_plugins_; }; -} // namespace behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner #endif // PLANNER_MANAGER_HPP_ diff --git a/planning/behavior_velocity_planner/srv/LoadPlugin.srv b/planning/autoware_behavior_velocity_planner/srv/LoadPlugin.srv similarity index 100% rename from planning/behavior_velocity_planner/srv/LoadPlugin.srv rename to planning/autoware_behavior_velocity_planner/srv/LoadPlugin.srv diff --git a/planning/behavior_velocity_planner/srv/UnloadPlugin.srv b/planning/autoware_behavior_velocity_planner/srv/UnloadPlugin.srv similarity index 100% rename from planning/behavior_velocity_planner/srv/UnloadPlugin.srv rename to planning/autoware_behavior_velocity_planner/srv/UnloadPlugin.srv diff --git a/planning/behavior_velocity_planner/test/src/test_node_interface.cpp b/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp similarity index 96% rename from planning/behavior_velocity_planner/test/src/test_node_interface.cpp rename to planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp index 935530b52e175..06c1bc48cf529 100644 --- a/planning/behavior_velocity_planner/test/src/test_node_interface.cpp +++ b/planning/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp @@ -15,15 +15,15 @@ #include "node.hpp" #include -#include -#include +#include +#include #include #include #include -using behavior_velocity_planner::BehaviorVelocityPlannerNode; +using autoware::behavior_velocity_planner::BehaviorVelocityPlannerNode; using planning_test_utils::PlanningInterfaceTestManager; std::shared_ptr generateTestManager() @@ -50,7 +50,7 @@ std::shared_ptr generateNode() const auto planning_test_utils_dir = ament_index_cpp::get_package_share_directory("planning_test_utils"); const auto behavior_velocity_planner_dir = - ament_index_cpp::get_package_share_directory("behavior_velocity_planner"); + ament_index_cpp::get_package_share_directory("autoware_behavior_velocity_planner"); const auto motion_velocity_smoother_dir = ament_index_cpp::get_package_share_directory("motion_velocity_smoother"); 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..b72625be999dd --- /dev/null +++ b/planning/autoware_planning_test_manager/README.md @@ -0,0 +1,92 @@ +# Autoware Planning 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/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/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 97% 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..9ee162ec02d1f 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,10 @@ #include "motion_utils/trajectory/conversion.hpp" -#include -#include +#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/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_ 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 90% 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..8e016e2b63391 100644 --- a/planning/static_centerline_generator/launch/static_centerline_generator.launch.xml +++ b/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml @@ -10,7 +10,7 @@ - + @@ -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 90% rename from planning/static_centerline_generator/package.xml rename to planning/autoware_static_centerline_generator/package.xml index 6573f6e439c43..56d30a715c006 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 @@ -43,9 +43,9 @@ ament_cmake_gmock ament_lint_auto + autoware_behavior_velocity_planner autoware_lint_common behavior_path_planner - behavior_velocity_planner ros_testing rosidl_interface_packages 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 100% rename from planning/static_centerline_generator/rviz/static_centerline_generator.rviz rename to planning/autoware_static_centerline_generator/rviz/static_centerline_generator.rviz diff --git a/planning/static_centerline_generator/scripts/app.py b/planning/autoware_static_centerline_generator/scripts/app.py similarity index 96% rename from planning/static_centerline_generator/scripts/app.py rename to planning/autoware_static_centerline_generator/scripts/app.py index c1cb0473da040..08bff8b80dcb7 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") 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 100% rename from planning/static_centerline_generator/scripts/centerline_updater_helper.py rename to planning/autoware_static_centerline_generator/scripts/centerline_updater_helper.py 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 89% 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 750b2e68b16b0..74002916bb23c 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,21 +12,22 @@ // 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" #include "map_loader/lanelet2_map_loader_node.hpp" #include "map_projection_loader/load_info_from_lanelet2_map.hpp" +#include "map_projection_loader/map_projection_loader.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 @@ -36,7 +37,6 @@ #include "std_msgs/msg/bool.hpp" #include "std_msgs/msg/float32.hpp" #include "std_msgs/msg/int32.hpp" -#include #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 { @@ -203,8 +204,10 @@ StaticCenterlineGeneratorNode::StaticCenterlineGeneratorNode( const auto selected_centerline = std::vector( c.centerline.begin() + traj_range_indices_.first, c.centerline.begin() + traj_range_indices_.second + 1); + const auto selected_route_lane_ids = get_route_lane_ids_from_points(selected_centerline); save_map( - lanelet2_output_file_path, CenterlineWithRoute{selected_centerline, c.route_lane_ids}); + lanelet2_output_file_path, + CenterlineWithRoute{selected_centerline, selected_route_lane_ids}); } }); sub_traj_resample_interval_ = create_subscription( @@ -246,7 +249,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."); }(); } @@ -279,6 +282,8 @@ void StaticCenterlineGeneratorNode::run() load_map(lanelet2_input_file_path); const auto centerline_with_route = generate_centerline_with_route(); traj_range_indices_ = std::make_pair(0, centerline_with_route.centerline.size() - 1); + + evaluate(centerline_with_route.route_lane_ids, centerline_with_route.centerline); save_map(lanelet2_output_file_path, centerline_with_route); centerline_with_route_ = centerline_with_route; @@ -303,22 +308,11 @@ CenterlineWithRoute StaticCenterlineGeneratorNode::generate_centerline_with_rout 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); - + const auto route_lane_ids = get_route_lane_ids_from_points(bag_centerline); 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 @@ -335,10 +329,28 @@ CenterlineWithRoute StaticCenterlineGeneratorNode::generate_centerline_with_rout return centerline_with_route; } +std::vector StaticCenterlineGeneratorNode::get_route_lane_ids_from_points( + const std::vector & points) +{ + const auto start_lanelets = route_handler_ptr_->getRoadLaneletsAtPose(points.front().pose); + const auto end_lanelets = route_handler_ptr_->getRoadLaneletsAtPose(points.back().pose); + if (start_lanelets.empty() || end_lanelets.empty()) { + RCLCPP_ERROR(get_logger(), "Nearest lanelets to the bag's points are not found."); + return std::vector{}; + } + + const lanelet::Id start_lanelet_id = start_lanelets.front().id(); + const lanelet::Id end_lanelet_id = end_lanelets.front().id(); + if (start_lanelet_id == end_lanelet_id) { + return std::vector{start_lanelet_id}; + } + return plan_route(start_lanelet_id, end_lanelet_id); +} + 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", @@ -347,21 +359,18 @@ void StaticCenterlineGeneratorNode::load_map(const std::string & lanelet2_input_ // load map by the map_loader package map_bin_ptr_ = [&]() -> HADMapBin::ConstSharedPtr { // load map - const auto map_projector_info = load_info_from_lanelet2_map(lanelet2_input_file_path); + map_projector_info_ = + std::make_unique(load_info_from_lanelet2_map(lanelet2_input_file_path)); const auto map_ptr = - Lanelet2MapLoaderNode::load_map(lanelet2_input_file_path, map_projector_info); + Lanelet2MapLoaderNode::load_map(lanelet2_input_file_path, *map_projector_info_); if (!map_ptr) { return nullptr; } - // NOTE: generate map projector for lanelet::write(). - // Without this, lat/lon of the generated LL2 map will be wrong. - map_projector_ = geography_utils::get_lanelet2_projector(map_projector_info); - - // NOTE: The original map is stored here since the various ids in the lanelet map will change - // after lanelet::utils::overwriteLaneletCenterline, and saving map will fail. + // NOTE: The original map is stored here since the centerline will be added to all the + // lanelet when lanelet::utils::overwriteLaneletCenterline is called. original_map_ptr_ = - Lanelet2MapLoaderNode::load_map(lanelet2_input_file_path, map_projector_info); + Lanelet2MapLoaderNode::load_map(lanelet2_input_file_path, *map_projector_info_); // overwrite more dense centerline lanelet::utils::overwriteLaneletsCenterline(map_ptr, 5.0, false); @@ -541,7 +550,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); @@ -637,18 +646,20 @@ void StaticCenterlineGeneratorNode::save_map( 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); + utils::update_centerline(original_map_ptr_, route_lanelets, c.centerline); RCLCPP_INFO(get_logger(), "Updated centerline in map."); // save map with modified center line - lanelet::write(lanelet2_output_file_path, *original_map_ptr_, *map_projector_); + std::filesystem::create_directory("/tmp/static_centerline_generator"); // TODO(murooka) + const auto map_projector = geography_utils::get_lanelet2_projector(*map_projector_info_); + 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/"}; + 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 78% 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..dfe5af68c270b 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,33 +12,33 @@ // 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 - #include "std_msgs/msg/bool.hpp" #include "std_msgs/msg/float32.hpp" #include "std_msgs/msg/int32.hpp" +#include "tier4_map_msgs/msg/map_projector_info.hpp" #include #include #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; +using tier4_map_msgs::msg::MapProjectorInfo; struct CenterlineWithRoute { @@ -66,6 +66,8 @@ class StaticCenterlineGeneratorNode : public rclcpp::Node // plan centerline CenterlineWithRoute generate_centerline_with_route(); + std::vector get_route_lane_ids_from_points( + const std::vector & points); void on_plan_path( const PlanPath::Request::SharedPtr request, const PlanPath::Response::SharedPtr response); @@ -80,7 +82,7 @@ class StaticCenterlineGeneratorNode : public rclcpp::Node lanelet::LaneletMapPtr original_map_ptr_{nullptr}; HADMapBin::ConstSharedPtr map_bin_ptr_{nullptr}; std::shared_ptr route_handler_ptr_{nullptr}; - std::unique_ptr map_projector_{nullptr}; + std::unique_ptr map_projector_info_{nullptr}; std::pair traj_range_indices_{0, 0}; std::optional centerline_with_route_{std::nullopt}; @@ -115,5 +117,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 91% rename from planning/static_centerline_generator/src/utils.cpp rename to planning/autoware_static_centerline_generator/src/utils.cpp index ddfd3e11036ce..2dbd82772f7ef 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 { @@ -32,12 +35,19 @@ nav_msgs::msg::Odometry::ConstSharedPtr convert_to_odometry(const geometry_msgs: return odometry_ptr; } -lanelet::Point3d createPoint3d(const double x, const double y, const double z = 19.0) +lanelet::Point3d createPoint3d(const double x, const double y, const double z) { lanelet::Point3d point(lanelet::utils::getId()); + + // position + point.x() = x; + point.y() = y; + point.z() = z; + + // attributes point.setAttribute("local_x", x); point.setAttribute("local_y", y); - point.setAttribute("ele", z); + // NOTE: It seems that the attribute "ele" is assigned automatically. return point; } @@ -73,11 +83,13 @@ geometry_msgs::msg::Pose get_center_pose( geometry_msgs::msg::Point middle_pos; middle_pos.x = center_line[middle_point_idx].x(); middle_pos.y = center_line[middle_point_idx].y(); + middle_pos.z = center_line[middle_point_idx].z(); // 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(); + next_middle_pos.z = center_line[middle_point_idx + 1].z(); // calculate middle pose geometry_msgs::msg::Pose middle_pose; @@ -116,13 +128,13 @@ PathWithLaneId get_path_with_lane_id( } void update_centerline( - RouteHandler & route_handler, const lanelet::ConstLanelets & lanelets, + lanelet::LaneletMapPtr lanelet_map_ptr, const lanelet::ConstLanelets & lanelets, const std::vector & new_centerline) { // get lanelet as reference to update centerline lanelet::Lanelets lanelets_ref; for (const auto & lanelet : lanelets) { - for (auto & lanelet_ref : route_handler.getLaneletMapPtr()->laneletLayer) { + for (auto & lanelet_ref : lanelet_map_ptr->laneletLayer) { if (lanelet_ref.id() == lanelet.id()) { lanelets_ref.push_back(lanelet_ref); } @@ -145,13 +157,13 @@ void update_centerline( // set center point centerline.push_back(center_point); - route_handler.getLaneletMapPtr()->add(center_point); + lanelet_map_ptr->add(center_point); break; } if (!centerline.empty()) { // set centerline - route_handler.getLaneletMapPtr()->add(centerline); + lanelet_map_ptr->add(centerline); lanelet_ref.setCenterline(centerline); // prepare new centerline @@ -163,7 +175,7 @@ void update_centerline( auto & lanelet_ref = lanelets_ref.at(lanelet_idx); // set centerline - route_handler.getLaneletMapPtr()->add(centerline); + lanelet_map_ptr->add(centerline); lanelet_ref.setCenterline(centerline); } } @@ -228,4 +240,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 82% rename from planning/static_centerline_generator/include/static_centerline_generator/utils.hpp rename to planning/autoware_static_centerline_generator/src/utils.hpp index c8cf8f8b90590..1d7eb1f18cc44 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 { @@ -42,7 +42,7 @@ PathWithLaneId get_path_with_lane_id( const double nearest_ego_yaw_threshold); void update_centerline( - RouteHandler & route_handler, const lanelet::ConstLanelets & lanelets, + lanelet::LaneletMapPtr lanelet_map_ptr, const lanelet::ConstLanelets & lanelets, const std::vector & new_centerline); MarkerArray create_footprint_marker( @@ -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 82% 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..dc3c26798b12d 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( @@ -58,7 +59,7 @@ def generate_test_description(): "config/behavior_path_planner.param.yaml", ), os.path.join( - get_package_share_directory("behavior_velocity_planner"), + get_package_share_directory("autoware_behavior_velocity_planner"), "config/behavior_velocity_planner.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/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/data_structs.hpp b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/data_structs.hpp index 8e7d1f67d3157..d7fd8b82bd71e 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/data_structs.hpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/data_structs.hpp @@ -14,7 +14,7 @@ #ifndef BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__DATA_STRUCTS_HPP_ #define BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__DATA_STRUCTS_HPP_ -#include "behavior_path_avoidance_module/data_structs.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/data_structs.hpp" namespace behavior_path_planner { diff --git a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp index 54a4a0c70486d..4ef4c0673c0c5 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/scene.hpp @@ -15,8 +15,8 @@ #ifndef BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__SCENE_HPP_ #define BEHAVIOR_PATH_AVOIDANCE_BY_LANE_CHANGE_MODULE__SCENE_HPP_ +#include "autoware_behavior_path_static_obstacle_avoidance_module/helper.hpp" #include "behavior_path_avoidance_by_lane_change_module/data_structs.hpp" -#include "behavior_path_avoidance_module/helper.hpp" #include "behavior_path_lane_change_module/scene.hpp" #include @@ -24,7 +24,7 @@ namespace behavior_path_planner { using AvoidanceDebugData = DebugData; -using helper::avoidance::AvoidanceHelper; +using helper::static_obstacle_avoidance::AvoidanceHelper; class AvoidanceByLaneChange : public NormalLaneChange { diff --git a/planning/behavior_path_avoidance_by_lane_change_module/package.xml b/planning/behavior_path_avoidance_by_lane_change_module/package.xml index 0f9f3f6dc9d42..84540618e152d 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/package.xml +++ b/planning/behavior_path_avoidance_by_lane_change_module/package.xml @@ -18,7 +18,7 @@ autoware_cmake eigen3_cmake_module - behavior_path_avoidance_module + autoware_behavior_path_static_obstacle_avoidance_module behavior_path_lane_change_module behavior_path_planner behavior_path_planner_common 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_by_lane_change_module/src/manager.cpp b/planning/behavior_path_avoidance_by_lane_change_module/src/manager.cpp index a3b28b4d63d06..c7c00d38956c1 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 @@ -14,8 +14,8 @@ #include "behavior_path_avoidance_by_lane_change_module/manager.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/parameter_helper.hpp" #include "behavior_path_avoidance_by_lane_change_module/data_structs.hpp" -#include "behavior_path_avoidance_module/parameter_helper.hpp" #include "tier4_autoware_utils/ros/parameter.hpp" #include "tier4_autoware_utils/ros/update_param.hpp" 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 6a41eccc22ba3..80ae361ee3ea1 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 @@ -14,13 +14,13 @@ #include "behavior_path_avoidance_by_lane_change_module/scene.hpp" -#include "behavior_path_avoidance_module/utils.hpp" +#include "autoware_behavior_path_static_obstacle_avoidance_module/utils.hpp" #include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "behavior_path_planner_common/utils/path_utils.hpp" #include "behavior_path_planner_common/utils/utils.hpp" -#include +#include #include #include #include @@ -103,13 +103,14 @@ void AvoidanceByLaneChange::updateSpecialData() if (avoidance_data_.target_objects.empty()) { direction_ = Direction::NONE; } else { - direction_ = utils::avoidance::isOnRight(avoidance_data_.target_objects.front()) + direction_ = utils::static_obstacle_avoidance::isOnRight(avoidance_data_.target_objects.front()) ? Direction::LEFT : Direction::RIGHT; } - utils::avoidance::updateRegisteredObject(registered_objects_, avoidance_data_.target_objects, p); - utils::avoidance::compensateDetectionLost( + utils::static_obstacle_avoidance::updateRegisteredObject( + registered_objects_, avoidance_data_.target_objects, p); + utils::static_obstacle_avoidance::compensateDetectionLost( registered_objects_, avoidance_data_.target_objects, avoidance_data_.other_objects); std::sort( @@ -145,7 +146,9 @@ void AvoidanceByLaneChange::fillAvoidanceTargetObjects( const auto [object_within_target_lane, object_outside_target_lane] = utils::path_safety_checker::separateObjectsByLanelets( *planner_data_->dynamic_object, data.current_lanelets, - utils::path_safety_checker::isPolygonOverlapLanelet); + [](const auto & obj, const auto & lane) { + return utils::path_safety_checker::isPolygonOverlapLanelet(obj, lane); + }); // Assume that the maximum allocation for data.other object is the sum of // objects_within_target_lane and object_outside_target_lane. The maximum allocation for @@ -164,7 +167,7 @@ void AvoidanceByLaneChange::fillAvoidanceTargetObjects( [](const auto & object) { ObjectData other_object; other_object.object = object; - other_object.reason = "OutOfTargetArea"; + other_object.info = ObjectInfo::OUT_OF_TARGET_AREA; return other_object; }); } @@ -220,28 +223,29 @@ std::optional AvoidanceByLaneChange::createObjectData( object_data.distance_factor = object_parameter.max_expand_ratio * clamp + 1.0; // Calc envelop polygon. - utils::avoidance::fillObjectEnvelopePolygon( + utils::static_obstacle_avoidance::fillObjectEnvelopePolygon( object_data, registered_objects_, object_closest_pose, p); // calc object centroid. object_data.centroid = return_centroid(object_data.envelope_poly); // Calc moving time. - utils::avoidance::fillObjectMovingTime(object_data, stopped_objects_, p); + utils::static_obstacle_avoidance::fillObjectMovingTime(object_data, stopped_objects_, p); object_data.direction = calcLateralDeviation(object_closest_pose, object_pose.position) > 0.0 ? Direction::LEFT : Direction::RIGHT; // Find the footprint point closest to the path, set to object_data.overhang_distance. - object_data.overhang_points = - utils::avoidance::calcEnvelopeOverhangDistance(object_data, data.reference_path); + object_data.overhang_points = utils::static_obstacle_avoidance::calcEnvelopeOverhangDistance( + object_data, data.reference_path); // Check whether the the ego should avoid the object. const auto & vehicle_width = planner_data_->parameters.vehicle_width; - utils::avoidance::fillAvoidanceNecessity(object_data, registered_objects_, vehicle_width, p); + utils::static_obstacle_avoidance::fillAvoidanceNecessity( + object_data, registered_objects_, vehicle_width, p); - utils::avoidance::fillLongitudinalAndLengthByClosestEnvelopeFootprint( + utils::static_obstacle_avoidance::fillLongitudinalAndLengthByClosestEnvelopeFootprint( data.reference_path_rough, getEgoPosition(), object_data); return object_data; } @@ -260,7 +264,7 @@ double AvoidanceByLaneChange::calcMinAvoidanceLength(const ObjectData & nearest_ avoidance_helper_->setData(planner_data_); const auto shift_length = avoidance_helper_->getShiftLength( - nearest_object, utils::avoidance::isOnRight(nearest_object), avoid_margin); + nearest_object, utils::static_obstacle_avoidance::isOnRight(nearest_object), avoid_margin); return avoidance_helper_->getMinAvoidanceDistance(shift_length); } 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..69ce87aabc7b4 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 @@ -67,8 +67,9 @@ std::shared_ptr generateNode() behavior_path_planner_dir + "/config/drivable_area_expansion.param.yaml", behavior_path_planner_dir + "/config/scene_module_manager.param.yaml", behavior_path_lane_change_module_dir + "/config/lane_change.param.yaml", - ament_index_cpp::get_package_share_directory("behavior_path_avoidance_module") + - "/config/avoidance.param.yaml", + ament_index_cpp::get_package_share_directory( + "autoware_behavior_path_static_obstacle_avoidance_module") + + "/config/static_obstacle_avoidance.param.yaml", ament_index_cpp::get_package_share_directory("behavior_path_avoidance_by_lane_change_module") + "/config/avoidance_by_lane_change.param.yaml"}); diff --git a/planning/behavior_path_avoidance_module/plugins.xml b/planning/behavior_path_avoidance_module/plugins.xml deleted file mode 100644 index f25677dad1e9a..0000000000000 --- a/planning/behavior_path_avoidance_module/plugins.xml +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/planning/behavior_path_dynamic_avoidance_module/plugins.xml b/planning/behavior_path_dynamic_avoidance_module/plugins.xml deleted file mode 100644 index fd2e1bc4137b7..0000000000000 --- a/planning/behavior_path_dynamic_avoidance_module/plugins.xml +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/planning/behavior_path_external_request_lane_change_module/plugins.xml b/planning/behavior_path_external_request_lane_change_module/plugins.xml deleted file mode 100644 index f3cc686837c38..0000000000000 --- a/planning/behavior_path_external_request_lane_change_module/plugins.xml +++ /dev/null @@ -1,4 +0,0 @@ - - - - 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..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 @@ -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,19 +544,46 @@ 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); // 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( @@ -508,7 +592,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 +624,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 +645,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/include/behavior_path_goal_planner_module/util.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp index b6f671cfc94f8..be3dd9ba96e38 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp @@ -16,6 +16,7 @@ #define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__UTIL_HPP_ #include "behavior_path_goal_planner_module/goal_searcher_base.hpp" +#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp" #include @@ -41,6 +42,7 @@ using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; +using Polygon2d = tier4_autoware_utils::Polygon2d; lanelet::ConstLanelets getPullOverLanes( const RouteHandler & route_handler, const bool left_side, const double backward_distance, @@ -85,6 +87,10 @@ PathWithLaneId extendPath( const PathWithLaneId & prev_module_path, const PathWithLaneId & reference_path, const Pose & extend_pose); +std::vector createPathFootPrints( + const PathWithLaneId & path, const double base_to_front, const double base_to_rear, + const double width); + // debug MarkerArray createPullOverAreaMarkerArray( const tier4_autoware_utils::MultiPolygon2d area_polygons, const std_msgs::msg::Header & header, 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..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 @@ -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(); } @@ -447,12 +533,10 @@ bool GoalPlannerModule::isExecutionRequested() const // check that goal is in current neighbor shoulder lane const bool goal_is_in_current_shoulder_lanes = std::invoke([&]() { - lanelet::ConstLanelet neighbor_shoulder_lane{}; for (const auto & lane : current_lanes) { - const bool has_shoulder_lane = - left_side_parking_ ? route_handler->getLeftShoulderLanelet(lane, &neighbor_shoulder_lane) - : route_handler->getRightShoulderLanelet(lane, &neighbor_shoulder_lane); - if (has_shoulder_lane && lanelet::utils::isInLanelet(goal_pose, neighbor_shoulder_lane)) { + const auto shoulder_lane = left_side_parking_ ? route_handler->getLeftShoulderLanelet(lane) + : route_handler->getRightShoulderLanelet(lane); + if (shoulder_lane && lanelet::utils::isInLanelet(goal_pose, *shoulder_lane)) { return true; } } @@ -501,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; } @@ -584,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); @@ -607,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) { @@ -645,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; } @@ -671,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: @@ -778,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; } @@ -848,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( @@ -859,22 +967,23 @@ std::optional> GoalPlannerModule::selectP continue; } - if (!hasEnoughDistance(pull_over_path)) { + if (!hasEnoughDistance(pull_over_path, long_tail_reference_path)) { continue; } 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 +1019,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 +1047,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 +1115,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 +1169,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 +1191,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 +1203,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 +1240,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 +1249,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 +1280,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 +1326,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 +1340,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 +1402,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 +1427,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 +1532,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 +1661,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 +1687,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 +1744,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 +1821,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 +1867,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 +1879,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); } @@ -1711,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; @@ -1723,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; @@ -1782,8 +1965,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_); @@ -1897,20 +2080,11 @@ bool GoalPlannerModule::isCrossingPossible( // Lambda function to get the neighboring lanelet based on left_side_parking_ auto getNeighboringLane = [&](const lanelet::ConstLanelet & lane) -> std::optional { - lanelet::ConstLanelet neighboring_lane{}; - if (left_side_parking_) { - if (route_handler->getLeftShoulderLanelet(lane, &neighboring_lane)) { - return neighboring_lane; - } else { - return route_handler->getLeftLanelet(lane); - } - } else { - if (route_handler->getRightShoulderLanelet(lane, &neighboring_lane)) { - return neighboring_lane; - } else { - return route_handler->getRightLanelet(lane); - } - } + const auto neighboring_lane = left_side_parking_ ? route_handler->getLeftShoulderLanelet(lane) + : route_handler->getRightShoulderLanelet(lane); + if (neighboring_lane) return neighboring_lane; + return left_side_parking_ ? route_handler->getLeftLanelet(lane) + : route_handler->getRightLanelet(lane); }; // Iterate through start_lane_sequence to find a path to end_lane_sequence @@ -1964,6 +2138,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 +2147,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 +2193,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 +2223,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 +2273,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 +2321,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 +2357,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 +2375,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 +2436,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 +2451,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 +2507,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 +2557,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 +2573,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 b168da61e6239..376adb178708a 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} { } @@ -220,11 +218,6 @@ std::optional ShiftPullOver::generatePullOverPath( shifted_path.path.points.push_back(p); } - // set the same z as the goal - for (auto & p : shifted_path.path.points) { - p.point.pose.position.z = goal_pose.position.z; - } - // set lane_id and velocity to shifted_path for (size_t i = path_shifter.getShiftLines().front().start_idx; i < shifted_path.path.points.size() - 1; ++i) { @@ -265,17 +258,39 @@ std::optional ShiftPullOver::generatePullOverPath( road_lane_reference_path_to_shift_end.points.back().point.pose); pull_over_path.debug_poses.push_back(prev_module_path_terminal_pose); - // check if the parking path will leave lanes - const auto drivable_lanes = - utils::generateDrivableLanesWithShoulderLanes(road_lanes, shoulder_lanes); - const auto & dp = planner_data_->drivable_area_expansion_parameters; - const auto expanded_lanes = utils::expandLanelets( - drivable_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset, - dp.drivable_area_types_to_skip); - const auto combined_drivable = utils::combineDrivableLanes( - expanded_lanes, previous_module_output_.drivable_area_info.drivable_lanes); - if (lane_departure_checker_.checkPathWillLeaveLane( - utils::transformToLanelets(combined_drivable), pull_over_path.getParkingPath())) { + // check if the parking path will leave drivable area and lanes + const bool is_in_parking_lots = std::invoke([&]() -> bool { + const auto & p = planner_data_->parameters; + const auto parking_lot_polygons = + lanelet::utils::query::getAllParkingLots(planner_data_->route_handler->getLaneletMapPtr()); + const auto path_footprints = goal_planner_utils::createPathFootPrints( + pull_over_path.getParkingPath(), p.base_link2front, p.base_link2rear, p.vehicle_width); + const auto is_footprint_in_any_polygon = [&parking_lot_polygons](const auto & footprint) { + return std::any_of( + parking_lot_polygons.begin(), parking_lot_polygons.end(), + [&footprint](const auto & polygon) { + return lanelet::geometry::within(footprint, lanelet::utils::to2D(polygon).basicPolygon()); + }); + }; + return std::all_of( + path_footprints.begin(), path_footprints.end(), + [&is_footprint_in_any_polygon](const auto & footprint) { + return is_footprint_in_any_polygon(footprint); + }); + }); + const bool is_in_lanes = std::invoke([&]() -> bool { + const auto drivable_lanes = + utils::generateDrivableLanesWithShoulderLanes(road_lanes, shoulder_lanes); + const auto & dp = planner_data_->drivable_area_expansion_parameters; + const auto expanded_lanes = utils::expandLanelets( + drivable_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset, + dp.drivable_area_types_to_skip); + const auto combined_drivable = utils::combineDrivableLanes( + expanded_lanes, previous_module_output_.drivable_area_info.drivable_lanes); + return !lane_departure_checker_.checkPathWillLeaveLane( + utils::transformToLanelets(combined_drivable), pull_over_path.getParkingPath()); + }); + if (!is_in_parking_lots && !is_in_lanes) { return {}; } diff --git a/planning/behavior_path_goal_planner_module/src/util.cpp b/planning/behavior_path_goal_planner_module/src/util.cpp index a43592deb3c4e..e94ab74a3bbed 100644 --- a/planning/behavior_path_goal_planner_module/src/util.cpp +++ b/planning/behavior_path_goal_planner_module/src/util.cpp @@ -55,12 +55,11 @@ lanelet::ConstLanelets getPullOverLanes( // todo(kosuek55): automatically calculates this distance. const double backward_distance_with_buffer = backward_distance + 100; - lanelet::ConstLanelet target_shoulder_lane{}; - if (route_handler::RouteHandler::getPullOverTarget( - route_handler.getShoulderLanelets(), goal_pose, &target_shoulder_lane)) { + const auto target_shoulder_lane = route_handler.getPullOverTarget(goal_pose); + if (target_shoulder_lane) { // pull over on shoulder lane return route_handler.getShoulderLaneletSequence( - target_shoulder_lane, goal_pose, backward_distance_with_buffer, forward_distance); + *target_shoulder_lane, goal_pose, backward_distance_with_buffer, forward_distance); } lanelet::ConstLanelet closest_lane{}; @@ -145,7 +144,9 @@ PredictedObjects extractObjectsInExpandedPullOverLanes( route_handler, left_side, backward_distance, forward_distance, bound_offset); const auto [objects_in_lanes, others] = utils::path_safety_checker::separateObjectsByLanelets( - objects, lanes, utils::path_safety_checker::isPolygonOverlapLanelet); + objects, lanes, [](const auto & obj, const auto & lanelet) { + return utils::path_safety_checker::isPolygonOverlapLanelet(obj, lanelet); + }); return objects_in_lanes; } @@ -432,4 +433,17 @@ PathWithLaneId extendPath( return extendPath(target_path, reference_path, extend_distance); } +std::vector createPathFootPrints( + const PathWithLaneId & path, const double base_to_front, const double base_to_rear, + const double width) +{ + std::vector footprints; + for (const auto & point : path.points) { + const auto & pose = point.point.pose; + footprints.push_back( + tier4_autoware_utils::toFootprint(pose, base_to_front, base_to_rear, width)); + } + return footprints; +} + } // namespace behavior_path_planner::goal_planner_utils diff --git a/planning/behavior_path_lane_change_module/README.md b/planning/behavior_path_lane_change_module/README.md index 62f35a053958a..9cbd864be9dbb 100644 --- a/planning/behavior_path_lane_change_module/README.md +++ b/planning/behavior_path_lane_change_module/README.md @@ -319,6 +319,171 @@ The detection area for the target lane can be expanded beyond its original bound +##### Object filtering + +```plantuml +@startuml +skinparam defaultTextAlignment center +skinparam backgroundColor #WHITE + +title NormalLaneChange::filterObjects Method Execution Flow + +start + +group "Filter Objects by Class" { +:Iterate through each object in objects list; +while (has not finished iterating through object list) is (TRUE) + if (current object type != param.object_types_to_check?) then (TRUE) + #LightPink:Remove current object; +else (FALSE) + :Keep current object; +endif +end while +end group + +if (object list is empty?) then (TRUE) + :Return empty result; + stop +else (FALSE) +endif + +group "Filter Oncoming Objects" #PowderBlue { +:Iterate through each object in target lane objects list; +while (has not finished iterating through object list?) is (TRUE) +:check object's yaw with reference to ego's yaw.; +if (yaw difference < 90 degree?) then (TRUE) + :Keep current object; +else (FALSE) +if (object is stopping?) then (TRUE) + :Keep current object; +else (FALSE) + #LightPink:Remove current object; +endif +endif +endwhile +end group + +if (object list is empty?) then (TRUE) + :Return empty result; + stop +else (FALSE) +endif + +group "Filter Objects Ahead Terminal" #Beige { +:Calculate lateral distance from ego to current lanes center; + +:Iterate through each object in objects list; +while (has not finished iterating through object list) is (TRUE) + :Get current object's polygon; + :Initialize distance to terminal from object to max; + while (has not finished iterating through object polygon's vertices) is (TRUE) + :Calculate object's lateral distance to end of lane; + :Update minimum distance to terminal from object; + end while + if (Is object's distance to terminal exceeds minimum lane change length?) then (TRUE) + #LightPink:Remove current object; + else (FALSE) + endif +end while +end group + +if (object list is empty?) then (TRUE) + :Return empty result; + stop +else (FALSE) +endif + +group "Filter Objects By Lanelets" #LightGreen { + +:Iterate through each object in objects list; +while (has not finished iterating through object list) is (TRUE) + :lateral distance diff = difference between object's lateral distance and ego's lateral distance to the current lanes' centerline.; + if (Object in target lane polygon, and lateral distance diff is more than half of ego's width?) then (TRUE) + :Add to target_lane_objects; + else (FALSE) + if (Object overlaps with backward target lanes?) then (TRUE) + :Add to target_lane_objects; + else (FALSE) + if (Object in current lane polygon?) then (TRUE) + :Add to current_lane_objects; + else (FALSE) + :Add to other_lane_objects; + endif + endif + endif +end while + +:Return target lanes object, current lanes object and other lanes object; +end group + +:Generate path from current lanes; + +if (path empty?) then (TRUE) + :Return empty result; + stop +else (FALSE) +endif + +group "Filter Target Lanes' objects" #LightCyan { + +:Iterate through each object in target lane objects list; +while (has not finished iterating through object list) is (TRUE) + :check object's velocity; + if(velocity is within threshold?) then (TRUE) + :Keep current object; + else (FALSE) + :check whether object is ahead of ego; + if(object is ahead of ego?) then (TRUE) + :keep current object; + else (FALSE) + #LightPink:remove current object; + endif + endif +endwhile +end group + +group "Filter Current Lanes' objects" #LightYellow { + +:Iterate through each object in current lane objects list; +while (has not finished iterating through object list) is (TRUE) + :check object's velocity; + if(velocity is within threshold?) then (TRUE) + :check whether object is ahead of ego; + if(object is ahead of ego?) then (TRUE) + :keep current object; + else (FALSE) + #LightPink:remove current object; + endif + else (FALSE) + #LightPink:remove current object; + endif +endwhile +end group + +group "Filter Other Lanes' objects" #Lavender { + +:Iterate through each object in other lane objects list; +while (has not finished iterating through object list) is (TRUE) + :check object's velocity; + if(velocity is within threshold?) then (TRUE) + :check whether object is ahead of ego; + if(object is ahead of ego?) then (TRUE) + :keep current object; + else (FALSE) + #LightPink:remove current object; + endif + else (FALSE) + #LightPink:remove current object; + endif +endwhile +end group + +:Trasform the objects into extended predicted object and return them as lane_change_target_objects; +stop + +@enduml +``` + ##### Collision check in prepare phase The ego vehicle may need to secure ample inter-vehicle distance ahead of the target vehicle before attempting a lane change. The flag `enable_collision_check_at_prepare_phase` can be enabled to gain this behavior. The following image illustrates the differences between the `false` and `true` cases. 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 4e886c33f832b..4c3d129ac687e 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 @@ -93,9 +93,6 @@ class LaneChangeInterface : public SceneModuleInterface MarkerArray getModuleVirtualWall() override; - TurnSignalInfo getCurrentTurnSignalInfo( - const PathWithLaneId & path, const TurnSignalInfo & original_turn_signal_info); - // TODO(someone): remove this, and use base class function [[deprecated]] BehaviorModuleOutput run() override { @@ -128,6 +125,18 @@ class LaneChangeInterface : public SceneModuleInterface ModuleStatus setInitState() const override { return ModuleStatus::WAITING_APPROVAL; }; + void updateRTCStatus( + const double start_distance, const double finish_distance, const bool safe, + const uint8_t & state) + { + for (const auto & [module_name, ptr] : rtc_interface_ptr_map_) { + if (ptr) { + ptr->updateCooperateStatus( + uuid_map_.at(module_name), safe, state, start_distance, finish_distance, clock_->now()); + } + } + } + void updateDebugMarker() const; void updateSteeringFactorPtr(const BehaviorModuleOutput & output); 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 7a76daff4bc55..76181f2195a84 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 @@ -30,10 +30,12 @@ using behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObject using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityAndPolygonStamped; using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped; using behavior_path_planner::utils::path_safety_checker::PredictedPathWithPolygon; +using data::lane_change::LanesPolygon; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; using route_handler::Direction; +using utils::path_safety_checker::ExtendedPredictedObjects; class NormalLaneChange : public LaneChangeBase { @@ -99,6 +101,8 @@ class NormalLaneChange : public LaneChangeBase bool isStoppedAtRedTrafficLight() const override; + TurnSignalInfo get_current_turn_signal_info() override; + protected: lanelet::ConstLanelets getCurrentLanes() const override; @@ -115,10 +119,26 @@ class NormalLaneChange : public LaneChangeBase const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes) const; - LaneChangeTargetObjects getTargetObjects( + ExtendedPredictedObjects getTargetObjects( + const LaneChangeLanesFilteredObjects & predicted_objects, + const lanelet::ConstLanelets & current_lanes) const; + + LaneChangeLanesFilteredObjects filterObjects( const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes) const; + void filterOncomingObjects(PredictedObjects & objects) const; + + void filterAheadTerminalObjects( + PredictedObjects & objects, const lanelet::ConstLanelets & current_lanes) const; + + void filterObjectsByLanelets( + const PredictedObjects & objects, const lanelet::ConstLanelets & current_lanes, + const lanelet::ConstLanelets & target_lanes, + std::vector & current_lane_objects, + std::vector & target_lane_objects, + std::vector & other_lane_objects) const; + PathWithLaneId getPrepareSegment( const lanelet::ConstLanelets & current_lanes, const double backward_path_length, const double prepare_length) const override; @@ -154,18 +174,11 @@ class NormalLaneChange : public LaneChangeBase bool isValidPath(const PathWithLaneId & path) const override; PathSafetyStatus isLaneChangePathSafe( - const LaneChangePath & lane_change_path, const LaneChangeTargetObjects & target_objects, - const utils::path_safety_checker::RSSparams & rss_params, const bool is_stuck, + const LaneChangePath & lane_change_path, + const ExtendedPredictedObjects & collision_check_objects, + const utils::path_safety_checker::RSSparams & rss_params, CollisionCheckDebugMap & debug_data) const; - LaneChangeTargetObjectIndices filterObject( - const PredictedObjects & objects, const lanelet::ConstLanelets & current_lanes, - const lanelet::ConstLanelets & target_lanes, - const lanelet::ConstLanelets & target_backward_lanes) const; - - std::vector filterObjectsInTargetLane( - const LaneChangeTargetObjects & objects, const lanelet::ConstLanelets & target_lanes) const; - //! @brief Check if the ego vehicle is in stuck by a stationary obstacle. //! @param obstacle_check_distance Distance to check ahead for any objects that might be //! obstructing ego path. It makes sense to use values like the maximum lane change distance. 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 e1d7725f93259..792e8924e5df6 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 @@ -187,6 +187,8 @@ class LaneChangeBase void resetStopPose() { lane_change_stop_pose_ = std::nullopt; } + virtual TurnSignalInfo get_current_turn_signal_info() = 0; + protected: virtual lanelet::ConstLanelets getCurrentLanes() const = 0; 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 fdaa15ff9bef9..0947f0e5aff94 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 @@ -20,6 +20,7 @@ #include #include +#include #include #include @@ -195,11 +196,11 @@ struct LaneChangeTargetObjectIndices std::vector other_lane{}; }; -struct LaneChangeTargetObjects +struct LaneChangeLanesFilteredObjects { - std::vector current_lane{}; - std::vector target_lane{}; - std::vector other_lane{}; + utils::path_safety_checker::ExtendedPredictedObjects current_lane{}; + utils::path_safety_checker::ExtendedPredictedObjects target_lane{}; + utils::path_safety_checker::ExtendedPredictedObjects other_lane{}; }; enum class LaneChangeModuleType { @@ -216,6 +217,13 @@ struct PathSafetyStatus bool is_safe{true}; bool is_object_coming_from_rear{false}; }; + +struct LanesPolygon +{ + std::optional current; + std::optional target; + std::vector target_backward; +}; } // namespace behavior_path_planner::data::lane_change #endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DATA_STRUCTS_HPP_ diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/debug_structs.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/debug_structs.hpp index 37d436f9949a2..fbdd742a8457b 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/debug_structs.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/debug_structs.hpp @@ -35,7 +35,7 @@ struct Debug LaneChangePaths valid_paths; CollisionCheckDebugMap collision_check_objects; CollisionCheckDebugMap collision_check_objects_after_approval; - LaneChangeTargetObjects filtered_objects; + LaneChangeLanesFilteredObjects filtered_objects; geometry_msgs::msg::Polygon execution_area; geometry_msgs::msg::Pose ego_pose; lanelet::ConstLanelets current_lanes; 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 cd4f55599d964..2d427213141b4 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 @@ -46,6 +46,7 @@ using behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObject using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityAndPolygonStamped; using behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped; using behavior_path_planner::utils::path_safety_checker::PredictedPathWithPolygon; +using data::lane_change::LanesPolygon; using data::lane_change::PathSafetyStatus; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; @@ -292,6 +293,10 @@ bool isWithinTurnDirectionLanes(const lanelet::ConstLanelet & lanelet, const Pol double calcPhaseLength( const double velocity, const double maximum_velocity, const double acceleration, const double time); + +LanesPolygon createLanesPolygon( + const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes, + const std::vector & target_backward_lanes); } // namespace behavior_path_planner::utils::lane_change namespace behavior_path_planner::utils::lane_change::debug diff --git a/planning/behavior_path_lane_change_module/plugins.xml b/planning/behavior_path_lane_change_module/plugins.xml index a598bc8176938..7df36919d8d54 100644 --- a/planning/behavior_path_lane_change_module/plugins.xml +++ b/planning/behavior_path_lane_change_module/plugins.xml @@ -1,6 +1,6 @@ - - + + diff --git a/planning/behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_lane_change_module/src/interface.cpp index d3ad4fb284f77..1669842117f9f 100644 --- a/planning/behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_lane_change_module/src/interface.cpp @@ -117,13 +117,18 @@ BehaviorModuleOutput LaneChangeInterface::plan() updateSteeringFactorPtr(output); if (module_type_->isAbortState()) { waitApproval(); - removeRTCStatus(); const auto candidate = planCandidate(); path_candidate_ = std::make_shared(candidate.path_candidate); updateRTCStatus( - candidate.start_distance_to_path_change, candidate.finish_distance_to_path_change); + std::numeric_limits::lowest(), std::numeric_limits::lowest(), true, + State::ABORTING); } else { clearWaitingApproval(); + const auto path = + assignToCandidate(module_type_->getLaneChangePath(), module_type_->getEgoPosition()); + updateRTCStatus( + path.start_distance_to_path_change, path.finish_distance_to_path_change, true, + State::RUNNING); } return output; @@ -135,8 +140,7 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval() BehaviorModuleOutput out = getPreviousModuleOutput(); module_type_->insertStopPoint(module_type_->getLaneChangeStatus().current_lanes, out.path); - out.turn_signal_info = - getCurrentTurnSignalInfo(out.path, getPreviousModuleOutput().turn_signal_info); + out.turn_signal_info = module_type_->get_current_turn_signal_info(); const auto & lane_change_debug = module_type_->getDebugData(); for (const auto & [uuid, data] : lane_change_debug.collision_check_objects) { @@ -148,7 +152,9 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval() stop_pose_ = module_type_->getStopPose(); if (!module_type_->isValidPath()) { - removeRTCStatus(); + updateRTCStatus( + std::numeric_limits::lowest(), std::numeric_limits::lowest(), true, + State::FAILED); path_candidate_ = std::make_shared(); return out; } @@ -157,7 +163,8 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval() path_candidate_ = std::make_shared(candidate.path_candidate); updateRTCStatus( - candidate.start_distance_to_path_change, candidate.finish_distance_to_path_change); + candidate.start_distance_to_path_change, candidate.finish_distance_to_path_change, + isExecutionReady(), State::WAITING_FOR_EXECUTION); is_abort_path_approved_ = false; return out; @@ -240,6 +247,9 @@ bool LaneChangeInterface::canTransitFailureState() if (module_type_->isStoppedAtRedTrafficLight()) { log_debug_throttled("Stopping at traffic light while in prepare phase. Cancel lane change"); module_type_->toCancelState(); + updateRTCStatus( + std::numeric_limits::lowest(), std::numeric_limits::lowest(), true, + State::FAILED); return true; } @@ -250,6 +260,9 @@ bool LaneChangeInterface::canTransitFailureState() if (module_type_->isAbleToReturnCurrentLane()) { log_debug_throttled("It's possible to return to current lane. Cancel lane change."); + updateRTCStatus( + std::numeric_limits::lowest(), std::numeric_limits::lowest(), true, + State::FAILED); return true; } } @@ -367,81 +380,4 @@ void LaneChangeInterface::updateSteeringFactorPtr( {output.start_distance_to_path_change, output.finish_distance_to_path_change}, PlanningBehavior::LANE_CHANGE, steering_factor_direction, SteeringFactor::APPROACHING, ""); } - -TurnSignalInfo LaneChangeInterface::getCurrentTurnSignalInfo( - const PathWithLaneId & path, const TurnSignalInfo & original_turn_signal_info) -{ - const auto & current_lanes = module_type_->getLaneChangeStatus().current_lanes; - const auto & is_valid = module_type_->getLaneChangeStatus().is_valid_path; - const auto & lane_change_path = module_type_->getLaneChangeStatus().lane_change_path; - const auto & lane_change_param = module_type_->getLaneChangeParam(); - - if ( - module_type_->getModuleType() != LaneChangeModuleType::NORMAL || current_lanes.empty() || - !is_valid) { - return original_turn_signal_info; - } - - // check direction - TurnSignalInfo current_turn_signal_info; - const auto & current_pose = module_type_->getEgoPose(); - const auto direction = module_type_->getDirection(); - if (direction == Direction::LEFT) { - current_turn_signal_info.turn_signal.command = TurnIndicatorsCommand::ENABLE_LEFT; - } else if (direction == Direction::RIGHT) { - current_turn_signal_info.turn_signal.command = TurnIndicatorsCommand::ENABLE_RIGHT; - } - - if (path.points.empty()) { - current_turn_signal_info.desired_start_point = current_pose; - current_turn_signal_info.required_start_point = current_pose; - current_turn_signal_info.desired_end_point = lane_change_path.info.lane_changing_end; - current_turn_signal_info.required_end_point = lane_change_path.info.lane_changing_end; - return current_turn_signal_info; - } - - const auto & min_length_for_turn_signal_activation = - lane_change_param.min_length_for_turn_signal_activation; - const auto & route_handler = module_type_->getRouteHandler(); - const auto & common_parameter = module_type_->getCommonParam(); - const auto shift_intervals = - route_handler->getLateralIntervalsToPreferredLane(current_lanes.back()); - const double next_lane_change_buffer = - utils::lane_change::calcMinimumLaneChangeLength(lane_change_param, shift_intervals); - const double & nearest_dist_threshold = common_parameter.ego_nearest_dist_threshold; - const double & nearest_yaw_threshold = common_parameter.ego_nearest_yaw_threshold; - const double & base_to_front = common_parameter.base_link2front; - - const double buffer = - next_lane_change_buffer + min_length_for_turn_signal_activation + base_to_front; - const double path_length = motion_utils::calcArcLength(path.points); - const size_t & current_nearest_seg_idx = - motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( - path.points, current_pose, nearest_dist_threshold, nearest_yaw_threshold); - const double dist_to_terminal = utils::getDistanceToEndOfLane(current_pose, current_lanes); - const auto start_pose = - motion_utils::calcLongitudinalOffsetPose(path.points, 0, std::max(path_length - buffer, 0.0)); - if (dist_to_terminal - base_to_front < buffer && start_pose) { - // modify turn signal - current_turn_signal_info.desired_start_point = *start_pose; - current_turn_signal_info.desired_end_point = lane_change_path.info.lane_changing_end; - current_turn_signal_info.required_start_point = current_turn_signal_info.desired_start_point; - current_turn_signal_info.required_end_point = current_turn_signal_info.desired_end_point; - - const auto & original_command = original_turn_signal_info.turn_signal.command; - if ( - original_command == TurnIndicatorsCommand::DISABLE || - original_command == TurnIndicatorsCommand::NO_COMMAND) { - return current_turn_signal_info; - } - - // check the priority of turn signals - return module_type_->getTurnSignalDecider().use_prior_turn_signal( - path, current_pose, current_nearest_seg_idx, original_turn_signal_info, - current_turn_signal_info, nearest_dist_threshold, nearest_yaw_threshold); - } - - // not in the vicinity of the end of the path. return original - return original_turn_signal_info; -} } // namespace behavior_path_planner diff --git a/planning/behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_lane_change_module/src/scene.cpp index 1e84fd41b3215..2d88a820e0fae 100644 --- a/planning/behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_lane_change_module/src/scene.cpp @@ -39,6 +39,8 @@ namespace behavior_path_planner { using motion_utils::calcSignedArcLength; using utils::lane_change::calcMinimumLaneChangeLength; +using utils::lane_change::createLanesPolygon; +using utils::path_safety_checker::isPolygonOverlapLanelet; using utils::traffic_light::getDistanceToNextTrafficLight; NormalLaneChange::NormalLaneChange( @@ -134,6 +136,83 @@ bool NormalLaneChange::isStoppedAtRedTrafficLight() const status_.lane_change_path.info.length.sum()); } +TurnSignalInfo NormalLaneChange::get_current_turn_signal_info() +{ + const auto original_turn_signal_info = prev_module_output_.turn_signal_info; + + const auto & current_lanes = getLaneChangeStatus().current_lanes; + const auto is_valid = getLaneChangeStatus().is_valid_path; + const auto & lane_change_path = getLaneChangeStatus().lane_change_path; + const auto & lane_change_param = getLaneChangeParam(); + + if (getModuleType() != LaneChangeModuleType::NORMAL || current_lanes.empty() || !is_valid) { + return original_turn_signal_info; + } + + // check direction + TurnSignalInfo current_turn_signal_info; + const auto & current_pose = getEgoPose(); + const auto direction = getDirection(); + if (direction == Direction::LEFT) { + current_turn_signal_info.turn_signal.command = TurnIndicatorsCommand::ENABLE_LEFT; + } else if (direction == Direction::RIGHT) { + current_turn_signal_info.turn_signal.command = TurnIndicatorsCommand::ENABLE_RIGHT; + } + + const auto & path = prev_module_output_.path; + if (path.points.empty()) { + current_turn_signal_info.desired_start_point = current_pose; + current_turn_signal_info.required_start_point = current_pose; + current_turn_signal_info.desired_end_point = lane_change_path.info.lane_changing_end; + current_turn_signal_info.required_end_point = lane_change_path.info.lane_changing_end; + return current_turn_signal_info; + } + + const auto min_length_for_turn_signal_activation = + lane_change_param.min_length_for_turn_signal_activation; + const auto & route_handler = getRouteHandler(); + const auto & common_parameter = getCommonParam(); + const auto shift_intervals = + route_handler->getLateralIntervalsToPreferredLane(current_lanes.back()); + const double next_lane_change_buffer = + utils::lane_change::calcMinimumLaneChangeLength(lane_change_param, shift_intervals); + const double nearest_dist_threshold = common_parameter.ego_nearest_dist_threshold; + const double nearest_yaw_threshold = common_parameter.ego_nearest_yaw_threshold; + const double base_to_front = common_parameter.base_link2front; + + const double buffer = + next_lane_change_buffer + min_length_for_turn_signal_activation + base_to_front; + const double path_length = motion_utils::calcArcLength(path.points); + const size_t current_nearest_seg_idx = + motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + path.points, current_pose, nearest_dist_threshold, nearest_yaw_threshold); + const double dist_to_terminal = utils::getDistanceToEndOfLane(current_pose, current_lanes); + const auto start_pose = + motion_utils::calcLongitudinalOffsetPose(path.points, 0, std::max(path_length - buffer, 0.0)); + if (dist_to_terminal - base_to_front < buffer && start_pose) { + // modify turn signal + current_turn_signal_info.desired_start_point = *start_pose; + current_turn_signal_info.desired_end_point = lane_change_path.info.lane_changing_end; + current_turn_signal_info.required_start_point = current_turn_signal_info.desired_start_point; + current_turn_signal_info.required_end_point = current_turn_signal_info.desired_end_point; + + const auto & original_command = original_turn_signal_info.turn_signal.command; + if ( + original_command == TurnIndicatorsCommand::DISABLE || + original_command == TurnIndicatorsCommand::NO_COMMAND) { + return current_turn_signal_info; + } + + // check the priority of turn signals + return getTurnSignalDecider().use_prior_turn_signal( + path, current_pose, current_nearest_seg_idx, original_turn_signal_info, + current_turn_signal_info, nearest_dist_threshold, nearest_yaw_threshold); + } + + // not in the vicinity of the end of the path. return original + return original_turn_signal_info; +} + LaneChangePath NormalLaneChange::getLaneChangePath() const { return status_.lane_change_path; @@ -276,7 +355,7 @@ void NormalLaneChange::insertStopPoint( } const double stop_point_buffer = lane_change_parameters_->backward_length_buffer_for_end_of_lane; - const auto target_objects = getTargetObjects(status_.current_lanes, status_.target_lanes); + const auto target_objects = filterObjects(status_.current_lanes, status_.target_lanes); double stopping_distance = distance_to_terminal - lane_change_buffer - stop_point_buffer; const auto is_valid_start_point = std::invoke([&]() -> bool { @@ -842,226 +921,270 @@ PathWithLaneId NormalLaneChange::getPrepareSegment( return prepare_segment; } -LaneChangeTargetObjects NormalLaneChange::getTargetObjects( +ExtendedPredictedObjects NormalLaneChange::getTargetObjects( + const LaneChangeLanesFilteredObjects & filtered_objects, + const lanelet::ConstLanelets & current_lanes) const +{ + ExtendedPredictedObjects target_objects = filtered_objects.target_lane; + const auto is_stuck = isVehicleStuck(current_lanes); + const auto chk_obj_in_curr_lanes = lane_change_parameters_->check_objects_on_current_lanes; + if (chk_obj_in_curr_lanes || is_stuck) { + target_objects.insert( + target_objects.end(), filtered_objects.current_lane.begin(), + filtered_objects.current_lane.end()); + } + + const auto chk_obj_in_other_lanes = lane_change_parameters_->check_objects_on_other_lanes; + if (chk_obj_in_other_lanes) { + target_objects.insert( + target_objects.end(), filtered_objects.other_lane.begin(), filtered_objects.other_lane.end()); + } + + return target_objects; +} + +LaneChangeLanesFilteredObjects NormalLaneChange::filterObjects( const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes) const { - const auto current_pose = getEgoPose(); - const auto & route_handler = *getRouteHandler(); + const auto & current_pose = getEgoPose(); + const auto & route_handler = getRouteHandler(); const auto & common_parameters = planner_data_->parameters; auto objects = *planner_data_->dynamic_object; utils::path_safety_checker::filterObjectsByClass( objects, lane_change_parameters_->object_types_to_check); - // get backward lanes - const auto backward_length = lane_change_parameters_->backward_lane_length; - const auto target_backward_lanes = behavior_path_planner::utils::getBackwardLanelets( - route_handler, target_lanes, current_pose, backward_length); + if (objects.objects.empty()) { + return {}; + } - lane_change_debug_.current_lanes = current_lanes; - lane_change_debug_.target_lanes = target_lanes; - lane_change_debug_.target_backward_lanes = target_backward_lanes; + filterOncomingObjects(objects); - // filter objects to get target object index - const auto target_obj_index = - filterObject(objects, current_lanes, target_lanes, target_backward_lanes); + if (objects.objects.empty()) { + return {}; + } - LaneChangeTargetObjects target_objects; - target_objects.current_lane.reserve(target_obj_index.current_lane.size()); - target_objects.target_lane.reserve(target_obj_index.target_lane.size()); - target_objects.other_lane.reserve(target_obj_index.other_lane.size()); + filterAheadTerminalObjects(objects, current_lanes); - // objects in current lane - const auto is_check_prepare_phase = check_prepare_phase(); - for (const auto & obj_idx : target_obj_index.current_lane) { - const auto extended_object = utils::lane_change::transform( - objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_, - is_check_prepare_phase); - target_objects.current_lane.push_back(extended_object); + if (objects.objects.empty()) { + return {}; } - // objects in target lane - for (const auto & obj_idx : target_obj_index.target_lane) { - const auto extended_object = utils::lane_change::transform( - objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_, - is_check_prepare_phase); - target_objects.target_lane.push_back(extended_object); - } + std::vector target_lane_objects; + std::vector current_lane_objects; + std::vector other_lane_objects; + + filterObjectsByLanelets( + objects, current_lanes, target_lanes, current_lane_objects, target_lane_objects, + other_lane_objects); + + const auto is_within_vel_th = [](const auto & object) -> bool { + constexpr double min_vel_th = 1.0; + constexpr double max_vel_th = std::numeric_limits::max(); + return utils::path_safety_checker::filter::velocity_filter(object, min_vel_th, max_vel_th); + }; - // objects in other lane - for (const auto & obj_idx : target_obj_index.other_lane) { - const auto extended_object = utils::lane_change::transform( - objects.objects.at(obj_idx), common_parameters, *lane_change_parameters_, - is_check_prepare_phase); - target_objects.other_lane.push_back(extended_object); + const auto path = + route_handler->getCenterLinePath(current_lanes, 0.0, std::numeric_limits::max()); + + if (path.points.empty()) { + return {}; } - return target_objects; + const auto is_ahead_of_ego = [&path, ¤t_pose](const auto & object) { + const auto obj_polygon = tier4_autoware_utils::toPolygon2d(object).outer(); + + double max_dist_ego_to_obj = std::numeric_limits::lowest(); + for (const auto & polygon_p : obj_polygon) { + const auto obj_p = tier4_autoware_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); + const auto dist_ego_to_obj = calcSignedArcLength(path.points, current_pose.position, obj_p); + max_dist_ego_to_obj = std::max(dist_ego_to_obj, max_dist_ego_to_obj); + } + return max_dist_ego_to_obj >= 0.0; + }; + + utils::path_safety_checker::filterObjects( + target_lane_objects, [&](const PredictedObject & object) { + return (is_within_vel_th(object) || is_ahead_of_ego(object)); + }); + + utils::path_safety_checker::filterObjects( + other_lane_objects, [&](const PredictedObject & object) { + return is_within_vel_th(object) && is_ahead_of_ego(object); + }); + + utils::path_safety_checker::filterObjects( + current_lane_objects, [&](const PredictedObject & object) { + return is_within_vel_th(object) && is_ahead_of_ego(object); + }); + + LaneChangeLanesFilteredObjects lane_change_target_objects; + + const auto is_check_prepare_phase = check_prepare_phase(); + std::for_each(target_lane_objects.begin(), target_lane_objects.end(), [&](const auto & object) { + auto extended_predicted_object = utils::lane_change::transform( + object, common_parameters, *lane_change_parameters_, is_check_prepare_phase); + lane_change_target_objects.target_lane.push_back(extended_predicted_object); + }); + + std::for_each(current_lane_objects.begin(), current_lane_objects.end(), [&](const auto & object) { + auto extended_predicted_object = utils::lane_change::transform( + object, common_parameters, *lane_change_parameters_, is_check_prepare_phase); + lane_change_target_objects.current_lane.push_back(extended_predicted_object); + }); + + std::for_each(other_lane_objects.begin(), other_lane_objects.end(), [&](const auto & object) { + auto extended_predicted_object = utils::lane_change::transform( + object, common_parameters, *lane_change_parameters_, is_check_prepare_phase); + lane_change_target_objects.other_lane.push_back(extended_predicted_object); + }); + + lane_change_debug_.filtered_objects = lane_change_target_objects; + + return lane_change_target_objects; +} + +void NormalLaneChange::filterOncomingObjects(PredictedObjects & objects) const +{ + const auto & current_pose = getEgoPose(); + + const auto is_same_direction = [&](const PredictedObject & object) { + const auto & object_pose = object.kinematics.initial_pose_with_covariance.pose; + return !utils::path_safety_checker::isTargetObjectOncoming(current_pose, object_pose); + }; + + // Perception noise could make stationary objects seem opposite the ego vehicle; check the + // velocity to prevent this. + const auto is_stopped_object = [](const auto & object) -> bool { + constexpr double min_vel_th = -0.5; + constexpr double max_vel_th = 0.5; + return utils::path_safety_checker::filter::velocity_filter(object, min_vel_th, max_vel_th); + }; + + utils::path_safety_checker::filterObjects(objects, [&](const PredictedObject & object) { + const auto same_direction = is_same_direction(object); + if (same_direction) { + return true; + } + + return is_stopped_object(object); + }); +} + +void NormalLaneChange::filterAheadTerminalObjects( + PredictedObjects & objects, const lanelet::ConstLanelets & current_lanes) const +{ + const auto & current_pose = getEgoPose(); + const auto & route_handler = getRouteHandler(); + const auto minimum_lane_change_length = utils::lane_change::calcMinimumLaneChangeLength( + route_handler, current_lanes.back(), *lane_change_parameters_, direction_); + + const auto dist_ego_to_current_lanes_center = + lanelet::utils::getLateralDistanceToClosestLanelet(current_lanes, current_pose); + + // ignore object that are ahead of terminal lane change start + utils::path_safety_checker::filterObjects(objects, [&](const PredictedObject & object) { + const auto obj_polygon = tier4_autoware_utils::toPolygon2d(object).outer(); + // ignore object that are ahead of terminal lane change start + auto distance_to_terminal_from_object = std::numeric_limits::max(); + for (const auto & polygon_p : obj_polygon) { + const auto obj_p = tier4_autoware_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); + Pose polygon_pose; + polygon_pose.position = obj_p; + polygon_pose.orientation = object.kinematics.initial_pose_with_covariance.pose.orientation; + const auto dist = utils::getDistanceToEndOfLane(polygon_pose, current_lanes); + distance_to_terminal_from_object = std::min(dist_ego_to_current_lanes_center, dist); + } + + return (minimum_lane_change_length > distance_to_terminal_from_object); + }); } -LaneChangeTargetObjectIndices NormalLaneChange::filterObject( +void NormalLaneChange::filterObjectsByLanelets( const PredictedObjects & objects, const lanelet::ConstLanelets & current_lanes, - const lanelet::ConstLanelets & target_lanes, - const lanelet::ConstLanelets & target_backward_lanes) const + const lanelet::ConstLanelets & target_lanes, std::vector & current_lane_objects, + std::vector & target_lane_objects, + std::vector & other_lane_objects) const { - const auto current_pose = getEgoPose(); + const auto & current_pose = getEgoPose(); const auto & route_handler = getRouteHandler(); const auto & common_parameters = planner_data_->parameters; - const auto minimum_lane_change_length = calcMinimumLaneChangeLength( - route_handler, current_lanes.back(), *lane_change_parameters_, direction_); + const auto check_optional_polygon = [](const auto & object, const auto & polygon) { + return polygon && isPolygonOverlapLanelet(object, *polygon); + }; - // Guard - if (objects.objects.empty()) { - return {}; - } + // get backward lanes + const auto backward_length = lane_change_parameters_->backward_lane_length; + const auto target_backward_lanes = + utils::getPrecedingLanelets(*route_handler, target_lanes, current_pose, backward_length); - // Get path - const auto path = - 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()); + { + lane_change_debug_.current_lanes = current_lanes; + lane_change_debug_.target_lanes = target_lanes; + + // TODO(Azu) change the type to std::vector + lane_change_debug_.target_backward_lanes.clear(); + std::for_each( + target_backward_lanes.begin(), target_backward_lanes.end(), + [&](const lanelet::ConstLanelets & target_backward_lane) { + lane_change_debug_.target_backward_lanes.insert( + lane_change_debug_.target_backward_lanes.end(), target_backward_lane.begin(), + target_backward_lane.end()); + }); + } - const auto current_polygon = - utils::lane_change::createPolygon(current_lanes, 0.0, std::numeric_limits::max()); const auto expanded_target_lanes = utils::lane_change::generateExpandedLanelets( target_lanes, direction_, lane_change_parameters_->lane_expansion_left_offset, lane_change_parameters_->lane_expansion_right_offset); - const auto target_polygon = utils::lane_change::createPolygon( - expanded_target_lanes, 0.0, std::numeric_limits::max()); + + const auto lanes_polygon = + createLanesPolygon(current_lanes, expanded_target_lanes, target_backward_lanes); const auto dist_ego_to_current_lanes_center = lanelet::utils::getLateralDistanceToClosestLanelet(current_lanes, current_pose); - std::vector> target_backward_polygons; - for (const auto & target_backward_lane : target_backward_lanes) { - // Check to see is target_backward_lane is in current_lanes - // Without this check, current lane object might be treated as target lane object - const auto is_current_lane = [&](const lanelet::ConstLanelet & current_lane) { - return current_lane.id() == target_backward_lane.id(); - }; - - if (std::any_of(current_lanes.begin(), current_lanes.end(), is_current_lane)) { - continue; - } - lanelet::ConstLanelets lanelet{target_backward_lane}; - auto lane_polygon = - utils::lane_change::createPolygon(lanelet, 0.0, std::numeric_limits::max()); - target_backward_polygons.push_back(lane_polygon); + { + const auto reserve_size = objects.objects.size(); + current_lane_objects.reserve(reserve_size); + target_lane_objects.reserve(reserve_size); + other_lane_objects.reserve(reserve_size); } - LaneChangeTargetObjectIndices filtered_obj_indices; - for (size_t i = 0; i < objects.objects.size(); ++i) { - const auto & object = objects.objects.at(i); - const auto obj_velocity_norm = std::hypot( - object.kinematics.initial_twist_with_covariance.twist.linear.x, - object.kinematics.initial_twist_with_covariance.twist.linear.y); - const auto extended_object = utils::lane_change::transform( - object, common_parameters, *lane_change_parameters_, check_prepare_phase()); - - const auto obj_polygon = tier4_autoware_utils::toPolygon2d(object); - - // calc distance from the current ego position - double max_dist_ego_to_obj = std::numeric_limits::lowest(); - double min_dist_ego_to_obj = std::numeric_limits::max(); - const auto obj_polygon_outer = obj_polygon.outer(); - for (const auto & polygon_p : obj_polygon_outer) { - const auto obj_p = tier4_autoware_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); - const double dist_ego_to_obj = calcSignedArcLength(path.points, current_pose.position, obj_p); - max_dist_ego_to_obj = std::max(dist_ego_to_obj, max_dist_ego_to_obj); - min_dist_ego_to_obj = std::min(dist_ego_to_obj, min_dist_ego_to_obj); - } - - const auto is_lateral_far = [&]() { + for (const auto & object : objects.objects) { + const auto is_lateral_far = std::invoke([&]() -> bool { const auto dist_object_to_current_lanes_center = lanelet::utils::getLateralDistanceToClosestLanelet( current_lanes, object.kinematics.initial_pose_with_covariance.pose); const auto lateral = dist_object_to_current_lanes_center - dist_ego_to_current_lanes_center; return std::abs(lateral) > (common_parameters.vehicle_width / 2); - }; - - // ignore object that are ahead of terminal lane change start - { - double distance_to_terminal_from_object = std::numeric_limits::max(); - for (const auto & polygon_p : obj_polygon_outer) { - const auto obj_p = tier4_autoware_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); - Pose polygon_pose; - polygon_pose.position = obj_p; - polygon_pose.orientation = object.kinematics.initial_pose_with_covariance.pose.orientation; - const double dist = utils::getDistanceToEndOfLane(polygon_pose, current_lanes); - if (dist < distance_to_terminal_from_object) { - distance_to_terminal_from_object = dist; - } - } - if (minimum_lane_change_length > distance_to_terminal_from_object) { - continue; - } - } + }); - // ignore static object that are behind the ego vehicle - if (obj_velocity_norm < 1.0 && max_dist_ego_to_obj < 0.0) { + if (check_optional_polygon(object, lanes_polygon.target) && is_lateral_far) { + target_lane_objects.push_back(object); continue; } - // check if the object intersects with target lanes - if (target_polygon && boost::geometry::intersects(target_polygon.value(), obj_polygon)) { - // TODO(watanabe): ignore static parked object that are in front of the ego vehicle in target - // lanes - - if (max_dist_ego_to_obj >= 0 || is_lateral_far()) { - filtered_obj_indices.target_lane.push_back(i); - continue; - } - } - - const auto check_backward_polygon = [&obj_polygon](const auto & target_backward_polygon) { - return target_backward_polygon && - boost::geometry::intersects(target_backward_polygon.value(), obj_polygon); - }; + const auto is_overlap_target_backward = std::invoke([&]() -> bool { + const auto check_backward_polygon = [&object](const auto & target_backward_polygon) { + return isPolygonOverlapLanelet(object, target_backward_polygon); + }; + return std::any_of( + lanes_polygon.target_backward.begin(), lanes_polygon.target_backward.end(), + check_backward_polygon); + }); // check if the object intersects with target backward lanes - if ( - !target_backward_polygons.empty() && - std::any_of( - target_backward_polygons.begin(), target_backward_polygons.end(), check_backward_polygon)) { - filtered_obj_indices.target_lane.push_back(i); + if (is_overlap_target_backward) { + target_lane_objects.push_back(object); continue; } - // check if the object intersects with current lanes - if ( - current_polygon && boost::geometry::intersects(current_polygon.value(), obj_polygon) && - max_dist_ego_to_obj >= 0.0) { + if (check_optional_polygon(object, lanes_polygon.current)) { // check only the objects that are in front of the ego vehicle - filtered_obj_indices.current_lane.push_back(i); + current_lane_objects.push_back(object); continue; } - // ignore all objects that are behind the ego vehicle and not on the current and target - // lanes - if (max_dist_ego_to_obj < 0.0) { - continue; - } - - filtered_obj_indices.other_lane.push_back(i); - } - - return filtered_obj_indices; -} - -std::vector NormalLaneChange::filterObjectsInTargetLane( - const LaneChangeTargetObjects & objects, const lanelet::ConstLanelets & target_lanes) const -{ - const auto target_polygon = - utils::lane_change::createPolygon(target_lanes, 0.0, std::numeric_limits::max()); - std::vector filtered_objects{}; - if (target_polygon) { - for (auto & obj : objects.target_lane) { - const auto obj_polygon = tier4_autoware_utils::toPolygon2d(obj.initial_pose.pose, obj.shape); - if (boost::geometry::intersects(target_polygon.value(), obj_polygon)) { - filtered_objects.push_back(obj); - } - } + other_lane_objects.push_back(object); } - - return filtered_objects; } PathWithLaneId NormalLaneChange::getTargetSegment( @@ -1241,8 +1364,8 @@ bool NormalLaneChange::getLaneChangePaths( return false; } - const auto target_objects = getTargetObjects(current_lanes, target_lanes); - lane_change_debug_.filtered_objects = target_objects; + const auto filtered_objects = filterObjects(current_lanes, target_lanes); + const auto target_objects = getTargetObjects(filtered_objects, current_lanes); const auto prepare_durations = calcPrepareDuration(current_lanes, target_lanes); @@ -1466,13 +1589,11 @@ bool NormalLaneChange::getLaneChangePaths( } candidate_paths->push_back(*candidate_path); - std::vector filtered_objects = - filterObjectsInTargetLane(target_objects, target_lanes); if ( - !is_stuck && - utils::lane_change::passParkedObject( - route_handler, *candidate_path, filtered_objects, lane_change_buffer, is_goal_in_route, - *lane_change_parameters_, lane_change_debug_.collision_check_objects)) { + !is_stuck && utils::lane_change::passParkedObject( + route_handler, *candidate_path, filtered_objects.target_lane, + lane_change_buffer, is_goal_in_route, *lane_change_parameters_, + lane_change_debug_.collision_check_objects)) { debug_print( "Reject: parking vehicle exists in the target lane, and the ego is not in stuck. Skip " "lane change."); @@ -1485,8 +1606,7 @@ bool NormalLaneChange::getLaneChangePaths( } const auto [is_safe, is_object_coming_from_rear] = isLaneChangePathSafe( - *candidate_path, target_objects, rss_params, is_stuck, - lane_change_debug_.collision_check_objects); + *candidate_path, target_objects, rss_params, lane_change_debug_.collision_check_objects); if (is_safe) { debug_print("ACCEPT!!!: it is valid and safe!"); @@ -1653,13 +1773,12 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const const auto & current_lanes = status_.current_lanes; const auto & target_lanes = status_.target_lanes; - const auto target_objects = getTargetObjects(current_lanes, target_lanes); - lane_change_debug_.filtered_objects = target_objects; + const auto filtered_objects = filterObjects(current_lanes, target_lanes); + const auto target_objects = getTargetObjects(filtered_objects, current_lanes); CollisionCheckDebugMap debug_data; - const bool is_stuck = isVehicleStuck(current_lanes); const auto safety_status = isLaneChangePathSafe( - path, target_objects, lane_change_parameters_->rss_params_for_abort, is_stuck, debug_data); + path, target_objects, lane_change_parameters_->rss_params_for_abort, debug_data); { // only for debug purpose lane_change_debug_.collision_check_objects.clear(); @@ -1855,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, @@ -1891,12 +2010,17 @@ bool NormalLaneChange::calcAbortPath() } PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( - const LaneChangePath & lane_change_path, const LaneChangeTargetObjects & target_objects, - const utils::path_safety_checker::RSSparams & rss_params, const bool is_stuck, + const LaneChangePath & lane_change_path, const ExtendedPredictedObjects & collision_check_objects, + const utils::path_safety_checker::RSSparams & rss_params, CollisionCheckDebugMap & debug_data) const { PathSafetyStatus path_safety_status; + if (collision_check_objects.empty()) { + RCLCPP_DEBUG(logger_, "There is nothing to check."); + return path_safety_status; + } + const auto & path = lane_change_path.path; const auto & common_parameters = planner_data_->parameters; const auto current_pose = getEgoPose(); @@ -1915,21 +2039,8 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( const auto debug_predicted_path = utils::path_safety_checker::convertToPredictedPath(ego_predicted_path, time_resolution); - auto collision_check_objects = target_objects.target_lane; const auto current_lanes = getCurrentLanes(); - if (lane_change_parameters_->check_objects_on_current_lanes || is_stuck) { - collision_check_objects.insert( - collision_check_objects.end(), target_objects.current_lane.begin(), - target_objects.current_lane.end()); - } - - if (lane_change_parameters_->check_objects_on_other_lanes) { - collision_check_objects.insert( - collision_check_objects.end(), target_objects.other_lane.begin(), - target_objects.other_lane.end()); - } - const auto expanded_target_lanes = utils::lane_change::generateExpandedLanelets( lane_change_path.info.target_lanes, direction_, lane_change_parameters_->lane_expansion_left_offset, 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 bf08d97dcfe5a..4eccd00d78c09 100644 --- a/planning/behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/utils.cpp @@ -646,8 +646,14 @@ std::vector generateDrivableLanes( double getLateralShift(const LaneChangePath & path) { - const auto start_idx = path.info.shift_line.start_idx; - const auto end_idx = path.info.shift_line.end_idx; + if (path.shifted_path.shift_length.empty()) { + return 0.0; + } + + const auto start_idx = + std::min(path.info.shift_line.start_idx, path.shifted_path.shift_length.size() - 1); + const auto end_idx = + std::min(path.info.shift_line.end_idx, path.shifted_path.shift_length.size() - 1); return path.shifted_path.shift_length.at(end_idx) - path.shifted_path.shift_length.at(start_idx); } @@ -1198,6 +1204,28 @@ double calcPhaseLength( const auto length_with_max_velocity = maximum_velocity * duration; return std::min(length_with_acceleration, length_with_max_velocity); } + +LanesPolygon createLanesPolygon( + const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes, + const std::vector & target_backward_lanes) +{ + LanesPolygon lanes_polygon; + + lanes_polygon.current = + utils::lane_change::createPolygon(current_lanes, 0.0, std::numeric_limits::max()); + lanes_polygon.target = + utils::lane_change::createPolygon(target_lanes, 0.0, std::numeric_limits::max()); + + for (const auto & target_backward_lane : target_backward_lanes) { + auto lane_polygon = utils::lane_change::createPolygon( + target_backward_lane, 0.0, std::numeric_limits::max()); + + if (lane_polygon) { + lanes_polygon.target_backward.push_back(*lane_polygon); + } + } + return lanes_polygon; +} } // namespace behavior_path_planner::utils::lane_change namespace behavior_path_planner::utils::lane_change::debug 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/README.md b/planning/behavior_path_planner/README.md index 03f8c8d2a5696..a799fad0a1c36 100644 --- a/planning/behavior_path_planner/README.md +++ b/planning/behavior_path_planner/README.md @@ -24,17 +24,17 @@ Essentially, the module has three primary responsibilities: Behavior Path Planner has following scene modules -| Name | Description | Details | -| :----------------------- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :----------------------------------------------------------------- | -| Lane Following | this module generates reference path from lanelet centerline. | LINK | -| Avoidance | this module generates avoidance path when there is objects that should be avoid. | [LINK](../behavior_path_avoidance_module/README.md) | -| Dynamic Avoidance | WIP | [LINK](../behavior_path_dynamic_avoidance_module/README.md) | -| Avoidance By Lane Change | this module generates lane change path when there is objects that should be avoid. | [LINK](../behavior_path_avoidance_by_lane_change_module/README.md) | -| Lane Change | this module is performed when it is necessary and a collision check with other vehicles is cleared. | [LINK](../behavior_path_lane_change_module/README.md) | -| External Lane Change | WIP | LINK | -| Start Planner | this module is performed when ego-vehicle is in the road lane and goal is in the shoulder lane. ego-vehicle will stop at the goal. | [LINK](../behavior_path_goal_planner_module/README.md) | -| Goal Planner | this module is performed when ego-vehicle is stationary and footprint of ego-vehicle is included in shoulder lane. This module ends when ego-vehicle merges into the road. | [LINK](../behavior_path_start_planner_module/README.md) | -| Side Shift | (for remote control) shift the path to left or right according to an external instruction. | [LINK](../behavior_path_side_shift_module/README.md) | +| Name | Description | Details | +| :------------------------- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :---------------------------------------------------------------------------- | +| Lane Following | this module generates reference path from lanelet centerline. | LINK | +| Static Obstacle Avoidance | this module generates avoidance path when there is objects that should be avoid. | [LINK](../autoware_behavior_path_static_obstacle_avoidance_module/README.md) | +| Dynamic Obstacle Avoidance | WIP | [LINK](../autoware_behavior_path_dynamic_obstacle_avoidance_module/README.md) | +| Avoidance By Lane Change | this module generates lane change path when there is objects that should be avoid. | [LINK](../behavior_path_avoidance_by_lane_change_module/README.md) | +| Lane Change | this module is performed when it is necessary and a collision check with other vehicles is cleared. | [LINK](../behavior_path_lane_change_module/README.md) | +| External Lane Change | WIP | LINK | +| Goal Planner | this module is performed when ego-vehicle is in the road lane and goal is in the shoulder lane. ego-vehicle will stop at the goal. | [LINK](../behavior_path_goal_planner_module/README.md) | +| Start Planner | this module is performed when ego-vehicle is stationary and footprint of ego-vehicle is included in shoulder lane. This module ends when ego-vehicle merges into the road. | [LINK](../behavior_path_start_planner_module/README.md) | +| Side Shift | (for remote control) shift the path to left or right according to an external instruction. | [LINK](../behavior_path_side_shift_module/README.md) | !!! Note @@ -138,19 +138,19 @@ Enabling and disabling the modules in the behavior path planner is primarily man The `default_preset.yaml` file acts as a configuration file for enabling or disabling specific modules within the planner. It contains a series of arguments which represent the behavior path planner's modules or features. For example: -- `launch_avoidance_module`: Set to `true` to enable the avoidance module, or `false` to disable it. +- `launch_static_obstacle_avoidance_module`: Set to `true` to enable the avoidance module, or `false` to disable it. !!! note Click [here](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/planning/preset/default_preset.yaml) to view the `default_preset.yaml`. -The `behavior_path_planner.launch.xml` file references the settings defined in `default_preset.yaml` to apply the configurations when the behavior path planner's node is running. For instance, the parameter `avoidance.enable_module` in +The `behavior_path_planner.launch.xml` file references the settings defined in `default_preset.yaml` to apply the configurations when the behavior path planner's node is running. For instance, the parameter `static_obstacle_avoidance.enable_module` in ```xml - + ``` -corresponds to launch_avoidance_module from `default_preset.yaml`. +corresponds to launch_static_obstacle_avoidance_module from `default_preset.yaml`. Therefore, to enable or disable a module, simply set the corresponding module in `default_preset.yaml` to `true` or `false`. These changes will be applied upon the next launch of Autoware. @@ -245,12 +245,12 @@ behavior_path_planner ├── behavior_path_planner.param.yaml ├── drivable_area_expansion.param.yaml ├── scene_module_manager.param.yaml -├── avoidance -│ └── avoidance.param.yaml +├── static_obstacle_avoidance +│ └── static_obstacle_avoidance.param.yaml ├── avoidance_by_lc │ └── avoidance_by_lc.param.yaml -├── dynamic_avoidance -│ └── dynamic_avoidance.param.yaml +├── dynamic_obstacle_avoidance +│ └── dynamic_obstacle_avoidance.param.yaml ├── goal_planner │ └── goal_planner.param.yaml ├── lane_change 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 2c181489ba4c2..e5c3a76fd1c45 100644 --- a/planning/behavior_path_planner/config/behavior_path_planner.param.yaml +++ b/planning/behavior_path_planner/config/behavior_path_planner.param.yaml @@ -17,6 +17,7 @@ turn_signal_minimum_search_distance: 10.0 turn_signal_search_time: 3.0 turn_signal_shift_length_threshold: 0.3 + turn_signal_remaining_shift_length_threshold: 0.1 turn_signal_on_swerving: true enable_akima_spline_first: false diff --git a/planning/behavior_path_planner/config/scene_module_manager.param.yaml b/planning/behavior_path_planner/config/scene_module_manager.param.yaml index c2b6babc402a2..6cf8719b2ef83 100644 --- a/planning/behavior_path_planner/config/scene_module_manager.param.yaml +++ b/planning/behavior_path_planner/config/scene_module_manager.param.yaml @@ -59,7 +59,7 @@ priority: 1 max_module_size: 1 - avoidance: + static_obstacle_avoidance: enable_rtc: false enable_simultaneous_execution_as_approved_module: true enable_simultaneous_execution_as_candidate_module: false @@ -75,7 +75,7 @@ priority: 3 max_module_size: 1 - dynamic_avoidance: + dynamic_obstacle_avoidance: enable_rtc: false enable_simultaneous_execution_as_approved_module: true enable_simultaneous_execution_as_candidate_module: true 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/package.xml b/planning/behavior_path_planner/package.xml index 7f50c61a8343a..14220c09880de 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 @@ -41,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 @@ -54,7 +56,6 @@ motion_utils object_recognition_utils path_sampler - planning_test_utils pluginlib rclcpp rclcpp_components 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 b56d1a207f76d..f7d204d2bff87 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -260,6 +260,8 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam() p.turn_signal_search_time = declare_parameter("turn_signal_search_time"); p.turn_signal_shift_length_threshold = declare_parameter("turn_signal_shift_length_threshold"); + p.turn_signal_remaining_shift_length_threshold = + declare_parameter("turn_signal_remaining_shift_length_threshold"); p.turn_signal_on_swerving = declare_parameter("turn_signal_on_swerving"); p.enable_akima_spline_first = declare_parameter("enable_akima_spline_first"); 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/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_planner_common/docs/behavior_path_planner_turn_signal_design.md b/planning/behavior_path_planner_common/docs/behavior_path_planner_turn_signal_design.md index bfc22bacc8ede..4302b74dcf2c6 100644 --- a/planning/behavior_path_planner_common/docs/behavior_path_planner_turn_signal_design.md +++ b/planning/behavior_path_planner_common/docs/behavior_path_planner_turn_signal_design.md @@ -20,14 +20,15 @@ Currently, this algorithm can sometimes give unnatural (not wrong) blinkers in c ## Parameters for turn signal decider -| Name | Unit | Type | Description | Default value | -| :---------------------------------------------- | :--- | :----- | :--------------------------------------------------------------------------- | :------------ | -| turn_signal_intersection_search_distance | [m] | double | constant search distance to decide activation of blinkers at intersections | 30 | -| turn_signal_intersection_angle_threshold_degree | deg | double | angle threshold to determined the end point of intersection required section | 15 | -| turn_signal_minimum_search_distance | [m] | double | minimum search distance for avoidance and lane change | 10 | -| turn_signal_search_time | [s] | double | search time for to decide activation of blinkers | 3.0 | -| turn_signal_shift_length_threshold | [m] | double | shift length threshold to decide activation of blinkers | 0.3 | -| turn_signal_on_swerving | [-] | bool | flag to activate blinkers when swerving | true | +| Name | Unit | Type | Description | Default value | +| :---------------------------------------------- | :--- | :----- | :------------------------------------------------------------------------------------------------------------------------------ | :------------ | +| turn_signal_intersection_search_distance | [m] | double | constant search distance to decide activation of blinkers at intersections | 30 | +| turn_signal_intersection_angle_threshold_degree | deg | double | angle threshold to determined the end point of intersection required section | 15 | +| turn_signal_minimum_search_distance | [m] | double | minimum search distance for avoidance and lane change | 10 | +| turn_signal_search_time | [s] | double | search time for to decide activation of blinkers | 3.0 | +| turn_signal_shift_length_threshold | [m] | double | shift length threshold to decide activation of blinkers | 0.3 | +| turn_signal_remaining_shift_length_threshold | [m] | double | When the ego's current shift length minus its end shift length is less than this threshold, the turn signal will be turned off. | 0.1 | +| turn_signal_on_swerving | [-] | bool | flag to activate blinkers when swerving | true | Note that the default values for `turn_signal_intersection_search_distance` and `turn_signal_search_time` is strictly followed by [Japanese Road Traffic Laws](https://www.japaneselawtranslation.go.jp/ja/laws/view/2962). So if your country does not allow to use these default values, you should change these values in configuration files. 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..b6dc2997c11e8 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,11 +41,13 @@ #include #include #include +#include #include #include #include #include +#include #include #include #include @@ -67,6 +69,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; @@ -184,9 +187,11 @@ class SceneModuleInterface { RCLCPP_DEBUG(getLogger(), "%s %s", name_.c_str(), __func__); + if (getCurrentStatus() == ModuleStatus::SUCCESS) { + updateRTCStatusForSuccess(); + } + clearWaitingApproval(); - removeRTCStatus(); - publishRTCStatus(); unlockNewModuleLaunch(); unlockOutputPath(); steering_factor_interface_ptr_->clearSteeringFactors(); @@ -196,18 +201,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_) { @@ -503,13 +496,28 @@ 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()); } } } + void updateRTCStatusForSuccess() + { + for (const auto & [module_name, ptr] : rtc_interface_ptr_map_) { + if (ptr) { + if (ptr->isRegistered(uuid_map_.at(module_name))) { + ptr->updateCooperateStatus( + uuid_map_.at(module_name), true, State::SUCCEEDED, + std::numeric_limits::lowest(), std::numeric_limits::lowest(), + clock_->now()); + } + } + } + } + void setObjectsOfInterestData( const geometry_msgs::msg::Pose & obj_pose, const autoware_auto_perception_msgs::msg::Shape & obj_shape, const ColorName & color_name) 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..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 @@ -99,6 +99,16 @@ class SceneModuleManagerInterface observers_.erase(itr, observers_.end()); } + void publishRTCStatus() + { + for (const auto & [module_name, ptr] : rtc_interface_ptr_map_) { + if (ptr) { + ptr->removeExpiredCooperateStatus(); + ptr->publishCooperateStatus(rclcpp::Clock(RCL_ROS_TIME).now()); + } + } + } + void publishVirtualWall() const { using tier4_autoware_utils::appendMarkerArray; @@ -235,7 +245,6 @@ class SceneModuleManagerInterface std::for_each(observers_.begin(), observers_.end(), [](const auto & observer) { if (!observer.expired()) { observer.lock()->onExit(); - observer.lock()->publishRTCStatus(); } }); @@ -243,7 +252,6 @@ class SceneModuleManagerInterface if (idle_module_ptr_ != nullptr) { idle_module_ptr_->onExit(); - idle_module_ptr_->publishRTCStatus(); idle_module_ptr_.reset(); } diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_visitor.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_visitor.hpp index ffc5daa7aa2ff..1bce30b18edd7 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_visitor.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_visitor.hpp @@ -21,7 +21,7 @@ namespace behavior_path_planner { // Forward Declaration -class AvoidanceModule; +class StaticObstacleAvoidanceModule; class AvoidanceByLCModule; class ExternalRequestLaneChangeModule; class LaneChangeInterface; @@ -35,7 +35,7 @@ using tier4_planning_msgs::msg::AvoidanceDebugMsgArray; class SceneModuleVisitor { public: - void visitAvoidanceModule(const AvoidanceModule * module) const; + void visitAvoidanceModule(const StaticObstacleAvoidanceModule * module) const; std::shared_ptr getAvoidanceModuleDebugMsg() 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 1241f98daa747..dbe27d856bc40 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 @@ -54,6 +54,7 @@ struct BehaviorPathPlannerParameters double turn_signal_search_time; double turn_signal_minimum_search_distance; double turn_signal_shift_length_threshold; + double turn_signal_remaining_shift_length_threshold; bool turn_signal_on_swerving; bool enable_akima_spline_first; 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( diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp index e33c2596ab04d..a0b2d0afa0fa8 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp @@ -69,6 +69,12 @@ bool isCentroidWithinLanelet(const PredictedObject & object, const lanelet::Cons */ bool isPolygonOverlapLanelet(const PredictedObject & object, const lanelet::ConstLanelet & lanelet); +bool isPolygonOverlapLanelet( + const PredictedObject & object, const tier4_autoware_utils::Polygon2d & lanelet_polygon); + +bool isPolygonOverlapLanelet( + const PredictedObject & object, const lanelet::BasicPolygon2d & lanelet_polygon); + /** * @brief Filters objects based on various criteria. * @@ -279,6 +285,15 @@ void filterObjects(PredictedObjects & selected, PredictedObjects & removed, Func selected.objects.erase(partitioned, selected.objects.end()); } +template +void filterObjects( + std::vector & selected, std::vector & removed, Func filter) +{ + auto partitioned = std::partition(selected.begin(), selected.end(), filter); + removed.insert(removed.end(), partitioned, selected.end()); + selected.erase(partitioned, selected.end()); +} + /** * @brief Filters objects in the 'objects' container based on the provided filter function. * @@ -296,6 +311,13 @@ void filterObjects(PredictedObjects & objects, Func filter) [[maybe_unused]] PredictedObjects removed_objects{}; filterObjects(objects, removed_objects, filter); } + +template +void filterObjects(std::vector & objects, Func filter) +{ + [[maybe_unused]] std::vector removed_objects{}; + filterObjects(objects, removed_objects, filter); +} } // namespace behavior_path_planner::utils::path_safety_checker #endif // BEHAVIOR_PATH_PLANNER_COMMON__UTILS__PATH_SAFETY_CHECKER__OBJECTS_FILTERING_HPP_ 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 53c4706e49c10..c4cfed01450b7 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 @@ -43,7 +43,8 @@ using tier4_autoware_utils::Polygon2d; using vehicle_info_util::VehicleInfo; bool isTargetObjectOncoming( - const geometry_msgs::msg::Pose & vehicle_pose, const geometry_msgs::msg::Pose & object_pose); + const geometry_msgs::msg::Pose & vehicle_pose, const geometry_msgs::msg::Pose & object_pose, + const double angle_threshold = M_PI_2); bool isTargetObjectFront( const geometry_msgs::msg::Pose & ego_pose, const Polygon2d & obj_polygon, @@ -54,11 +55,11 @@ bool isTargetObjectFront( Polygon2d createExtendedPolygon( const Pose & base_link_pose, const vehicle_info_util::VehicleInfo & vehicle_info, - const double lon_length, const double lat_margin, const double is_stopped_obj, + const double lon_length, const double lat_margin, const bool is_stopped_obj, CollisionCheckDebug & debug); Polygon2d createExtendedPolygon( const Pose & obj_pose, const Shape & shape, const double lon_length, const double lat_margin, - const double is_stopped_obj, CollisionCheckDebug & debug); + const bool is_stopped_obj, CollisionCheckDebug & debug); PredictedPath convertToPredictedPath( const std::vector & path, const double time_resolution); diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp index 67f581123057e..880e55b64d170 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp @@ -94,9 +94,9 @@ class PathShifter void setLongitudinalAcceleration(const double longitudinal_acc); /** - * @brief Add shift point. You don't have to care about the start/end_idx. + * @brief Add shift line. You don't have to care about the start/end_idx. */ - void addShiftLine(const ShiftLine & point); + void addShiftLine(const ShiftLine & line); /** * @brief Set new shift point. You don't have to care about the start/end_idx. @@ -143,7 +143,7 @@ class PathShifter //////////////////////////////////////// static double calcFeasibleVelocityFromJerk( - const double lateral, const double jerk, const double distance); + const double lateral, const double jerk, const double longitudinal_distance); static double calcLateralDistFromJerk( const double longitudinal, const double jerk, const double velocity); @@ -196,12 +196,12 @@ class PathShifter std::pair, std::vector> calcBaseLengths( const double arclength, const double shift_length, const bool offset_back) const; - std::pair, std::vector> getBaseLengthsWithoutAccelLimit( - const double arclength, const double shift_length, const bool offset_back) const; + static std::pair, std::vector> getBaseLengthsWithoutAccelLimit( + const double arclength, const double shift_length, const bool offset_back); - std::pair, std::vector> getBaseLengthsWithoutAccelLimit( + static std::pair, std::vector> getBaseLengthsWithoutAccelLimit( const double arclength, const double shift_length, const double velocity, - const double longitudinal_acc, const double total_time, const bool offset_back) const; + const double longitudinal_acc, const double total_time, const bool offset_back); /** * @brief Calculate path index for shift_lines and set is_index_aligned_ to true. @@ -235,9 +235,9 @@ class PathShifter */ bool checkShiftLinesAlignment(const ShiftLineArray & shift_lines) const; - void addLateralOffsetOnIndexPoint(ShiftedPath * path, double offset, size_t index) const; + static void addLateralOffsetOnIndexPoint(ShiftedPath * path, double offset, size_t index); - void shiftBaseLength(ShiftedPath * path, double offset) const; + static void shiftBaseLength(ShiftedPath * path, double offset); void setBaseOffset(const double val) { 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 b25238a49333c..b61ef0579cab0 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 @@ -299,6 +299,10 @@ lanelet::ConstLanelets extendPrevLane( lanelet::ConstLanelets extendLanes( const std::shared_ptr route_handler, const lanelet::ConstLanelets & lanes); +std::vector getPrecedingLanelets( + const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanes, + const Pose & current_pose, const double backward_length); + lanelet::ConstLanelets getBackwardLanelets( const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanes, const Pose & current_pose, const double backward_length); 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/behavior_path_planner_common/src/turn_signal_decider.cpp b/planning/behavior_path_planner_common/src/turn_signal_decider.cpp index 320cc96577187..fb15391550980 100644 --- a/planning/behavior_path_planner_common/src/turn_signal_decider.cpp +++ b/planning/behavior_path_planner_common/src/turn_signal_decider.cpp @@ -615,7 +615,6 @@ std::pair TurnSignalDecider::getBehaviorTurnSignalInfo( const double current_shift_length, const bool is_driving_forward, const bool egos_lane_is_shifted, const bool override_ego_stopped_check, const bool is_pull_out) const { - constexpr double THRESHOLD = 0.1; const auto & p = parameters; const auto & rh = route_handler; const auto & ego_pose = self_odometry->pose.pose; @@ -674,7 +673,9 @@ std::pair TurnSignalDecider::getBehaviorTurnSignalInfo( } // If the vehicle does not shift anymore, we turn off the blinker - if (std::fabs(end_shift_length - current_shift_length) < THRESHOLD) { + if ( + std::fabs(end_shift_length - current_shift_length) < + p.turn_signal_remaining_shift_length_threshold) { return std::make_pair(TurnSignalInfo{}, true); } @@ -731,10 +732,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_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp b/planning/behavior_path_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp index 1aab58ac2ff6e..df48b48d51241 100644 --- a/planning/behavior_path_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp +++ b/planning/behavior_path_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp @@ -110,6 +110,14 @@ void OccupancyGridBasedCollisionDetector::setMap(const nav_msgs::msg::OccupancyG } } +static IndexXY position2index( + const nav_msgs::msg::OccupancyGrid & costmap, const geometry_msgs::msg::Point & position_local) +{ + const int index_x = position_local.x / costmap.info.resolution; + const int index_y = position_local.y / costmap.info.resolution; + return {index_x, index_y}; +} + void OccupancyGridBasedCollisionDetector::computeCollisionIndexes( int theta_index, std::vector & indexes_2d) { @@ -131,12 +139,11 @@ void OccupancyGridBasedCollisionDetector::computeCollisionIndexes( const double offset_x = std::cos(base_theta) * x - std::sin(base_theta) * y; const double offset_y = std::sin(base_theta) * x + std::cos(base_theta) * y; - geometry_msgs::msg::Pose pose_local; - pose_local.position.x = base_pose.position.x + offset_x; - pose_local.position.y = base_pose.position.y + offset_y; + geometry_msgs::msg::Point position_local; + position_local.x = base_pose.position.x + offset_x; + position_local.y = base_pose.position.y + offset_y; - const auto index = pose2index(costmap_, pose_local, param_.theta_size); - const auto index_2d = IndexXY{index.x, index.y}; + const auto index_2d = position2index(costmap_, position_local); indexes_2d.push_back(index_2d); }; 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 b8014deee9500..cdb4b778d3ab3 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 @@ -66,8 +66,21 @@ bool isCentroidWithinLanelet(const PredictedObject & object, const lanelet::Cons bool isPolygonOverlapLanelet(const PredictedObject & object, const lanelet::ConstLanelet & lanelet) { - const auto object_polygon = tier4_autoware_utils::toPolygon2d(object); const auto lanelet_polygon = utils::toPolygon2d(lanelet); + return isPolygonOverlapLanelet(object, lanelet_polygon); +} + +bool isPolygonOverlapLanelet( + const PredictedObject & object, const tier4_autoware_utils::Polygon2d & lanelet_polygon) +{ + const auto object_polygon = tier4_autoware_utils::toPolygon2d(object); + return !boost::geometry::disjoint(lanelet_polygon, object_polygon); +} + +bool isPolygonOverlapLanelet( + const PredictedObject & object, const lanelet::BasicPolygon2d & lanelet_polygon) +{ + const auto object_polygon = tier4_autoware_utils::toPolygon2d(object); return !boost::geometry::disjoint(lanelet_polygon, object_polygon); } @@ -341,11 +354,9 @@ TargetObjectsOnLane createTargetObjectsOnLane( }; 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); + const auto neighbor_shoulder_lane = route_handler->getLeftShoulderLanelet(target_lane); + if (neighbor_shoulder_lane) { + all_left_shoulder_lanelets.insert(all_left_shoulder_lanelets.end(), *neighbor_shoulder_lane); } }; 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 6390c45376b37..e1884e57f7221 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 @@ -43,9 +43,10 @@ void appendPointToPolygon(Polygon2d & polygon, const geometry_msgs::msg::Point & } bool isTargetObjectOncoming( - const geometry_msgs::msg::Pose & vehicle_pose, const geometry_msgs::msg::Pose & object_pose) + const geometry_msgs::msg::Pose & vehicle_pose, const geometry_msgs::msg::Pose & object_pose, + const double angle_threshold) { - return std::abs(calcYawDeviation(vehicle_pose, object_pose)) > M_PI_2; + return std::abs(calcYawDeviation(vehicle_pose, object_pose)) > angle_threshold; } bool isTargetObjectFront( @@ -90,7 +91,7 @@ bool isTargetObjectFront( Polygon2d createExtendedPolygon( const Pose & base_link_pose, const vehicle_info_util::VehicleInfo & vehicle_info, - const double lon_length, const double lat_margin, const double is_stopped_obj, + const double lon_length, const double lat_margin, const bool is_stopped_obj, CollisionCheckDebug & debug) { const double & base_to_front = vehicle_info.max_longitudinal_offset_m; @@ -131,7 +132,7 @@ Polygon2d createExtendedPolygon( Polygon2d createExtendedPolygon( const Pose & obj_pose, const Shape & shape, const double lon_length, const double lat_margin, - const double is_stopped_obj, CollisionCheckDebug & debug) + const bool is_stopped_obj, CollisionCheckDebug & debug) { const auto obj_polygon = tier4_autoware_utils::toPolygon2d(obj_pose, shape); if (obj_polygon.outer().empty()) { @@ -189,7 +190,7 @@ Polygon2d createExtendedPolygon( Polygon2d createExtendedPolygonAlongPath( const PathWithLaneId & planned_path, const Pose & base_link_pose, const vehicle_info_util::VehicleInfo & vehicle_info, const double lon_length, - const double lat_margin, const double is_stopped_obj, CollisionCheckDebug & debug) + const double lat_margin, const bool is_stopped_obj, CollisionCheckDebug & debug) { const double & base_to_front = vehicle_info.max_longitudinal_offset_m; const double & width = vehicle_info.vehicle_width_m; diff --git a/planning/behavior_path_planner_common/src/utils/path_shifter/path_shifter.cpp b/planning/behavior_path_planner_common/src/utils/path_shifter/path_shifter.cpp index 7a74ca598de8f..1ea555f4675ef 100644 --- a/planning/behavior_path_planner_common/src/utils/path_shifter/path_shifter.cpp +++ b/planning/behavior_path_planner_common/src/utils/path_shifter/path_shifter.cpp @@ -53,7 +53,7 @@ namespace behavior_path_planner using motion_utils::findNearestIndex; using motion_utils::insertOrientation; -using motion_utils::removeInvalidOrientationPoints; +using motion_utils::removeFirstInvalidOrientationPoints; using motion_utils::removeOverlapPoints; void PathShifter::setPath(const PathWithLaneId & path) @@ -116,7 +116,13 @@ bool PathShifter::generate( } for (const auto & shift_line : shift_lines_) { - int idx_gap = shift_line.end_idx - shift_line.start_idx; + if (shift_line.end_idx < shift_line.start_idx) { + RCLCPP_WARN_STREAM_THROTTLE( + logger_, clock_, 3000, "Invalid indices: end_idx is less than start_idx"); + return false; + } + + const auto idx_gap = shift_line.end_idx - shift_line.start_idx; if (idx_gap <= 1) { RCLCPP_WARN_STREAM_THROTTLE( logger_, clock_, 3000, @@ -149,14 +155,14 @@ bool PathShifter::generate( shifted_path->path.points = removeOverlapPoints(shifted_path->path.points); // Use orientation before shift to remove points in reverse order // before setting wrong azimuth orientation - removeInvalidOrientationPoints(shifted_path->path.points); + removeFirstInvalidOrientationPoints(shifted_path->path.points); size_t previous_size{shifted_path->path.points.size()}; do { previous_size = shifted_path->path.points.size(); // Set the azimuth orientation to the next point at each point insertOrientation(shifted_path->path.points, true); // Use azimuth orientation to remove points in reverse order - removeInvalidOrientationPoints(shifted_path->path.points); + removeFirstInvalidOrientationPoints(shifted_path->path.points); } while (previous_size != shifted_path->path.points.size()); // DEBUG @@ -185,7 +191,7 @@ void PathShifter::applyLinearShifter(ShiftedPath * shifted_path) const // For all path.points, for (size_t i = 0; i < shifted_path->path.points.size(); ++i) { // Set shift length. - double ith_shift_length; + double ith_shift_length = 0.0; if (i < shift_line.start_idx) { ith_shift_length = 0.0; } else if (shift_line.start_idx <= i && i <= shift_line.end_idx) { @@ -235,7 +241,8 @@ void PathShifter::applySplineShifter(ShiftedPath * shifted_path, const bool offs logger_, "base_distance = %s, base_length = %s", toStr(base_distance).c_str(), toStr(base_length).c_str()); - std::vector query_distance, query_length; + std::vector query_distance; + std::vector query_length; // For all path.points, // Note: start_idx is not included since shift = 0, @@ -257,7 +264,7 @@ void PathShifter::applySplineShifter(ShiftedPath * shifted_path, const bool offs } } - if (offset_back == true) { + if (offset_back) { // Apply shifting after shift for (size_t i = shift_line.end_idx; i < shifted_path->path.points.size(); ++i) { addLateralOffsetOnIndexPoint(shifted_path, delta_shift, i); @@ -272,7 +279,7 @@ void PathShifter::applySplineShifter(ShiftedPath * shifted_path, const bool offs } std::pair, std::vector> PathShifter::getBaseLengthsWithoutAccelLimit( - const double arclength, const double shift_length, const bool offset_back) const + const double arclength, const double shift_length, const bool offset_back) { const auto s = arclength; const auto l = shift_length; @@ -286,14 +293,13 @@ std::pair, std::vector> PathShifter::getBaseLengthsW std::pair, std::vector> PathShifter::getBaseLengthsWithoutAccelLimit( const double arclength, const double shift_length, const double velocity, - const double longitudinal_acc, const double total_time, const bool offset_back) const + const double longitudinal_acc, const double total_time, const bool offset_back) { - const auto & s = arclength; - const auto & l = shift_length; - const auto & v0 = velocity; - const auto & a = longitudinal_acc; - const auto & T = total_time; - const double t = T / 4; + const auto s = arclength; + const auto l = shift_length; + const auto v0 = velocity; + const auto a = longitudinal_acc; + const auto t = total_time / 4; const double s1 = std::min(v0 * t + 0.5 * a * t * t, s); const double v1 = v0 + a * t; @@ -322,7 +328,7 @@ std::pair, std::vector> PathShifter::calcBaseLengths return getBaseLengthsWithoutAccelLimit(arclength, shift_length, offset_back); } - const auto & S = arclength; + const auto S = arclength; const auto L = std::abs(shift_length); const auto T = a > acc_threshold ? (-v0 + std::sqrt(v0 * v0 + 2 * a * S)) / a : S / v0; const auto lateral_a_max = 8.0 * L / (T * T); @@ -512,8 +518,7 @@ void PathShifter::removeBehindShiftLineAndSetBaseOffset(const size_t nearest_idx setBaseOffset(new_base_offset); } -void PathShifter::addLateralOffsetOnIndexPoint( - ShiftedPath * path, double offset, size_t index) const +void PathShifter::addLateralOffsetOnIndexPoint(ShiftedPath * path, double offset, size_t index) { if (fabs(offset) < 1.0e-8) { return; @@ -527,10 +532,10 @@ void PathShifter::addLateralOffsetOnIndexPoint( path->shift_length.at(index) += offset; } -void PathShifter::shiftBaseLength(ShiftedPath * path, double offset) const +void PathShifter::shiftBaseLength(ShiftedPath * path, double offset) { - constexpr double BASE_OFFSET_THR = 1.0e-4; - if (std::abs(offset) > BASE_OFFSET_THR) { + constexpr double base_offset_thr = 1.0e-4; + if (std::abs(offset) > base_offset_thr) { for (size_t i = 0; i < path->path.points.size(); ++i) { addLateralOffsetOnIndexPoint(path, offset, i); } @@ -563,11 +568,11 @@ double PathShifter::calcShiftTimeFromJerk(const double lateral, const double jer } double PathShifter::calcFeasibleVelocityFromJerk( - const double lateral, const double jerk, const double longitudinal) + const double lateral, const double jerk, const double longitudinal_distance) { const double j = std::abs(jerk); const double l = std::abs(lateral); - const double d = std::abs(longitudinal); + const double d = std::abs(longitudinal_distance); if (j < 1.0e-8) { return 1.0e10; // TODO(Horibe) maybe invalid arg? } diff --git a/planning/behavior_path_planner_common/src/utils/path_utils.cpp b/planning/behavior_path_planner_common/src/utils/path_utils.cpp index 1d51426793de8..d11bc5a68e9b5 100644 --- a/planning/behavior_path_planner_common/src/utils/path_utils.cpp +++ b/planning/behavior_path_planner_common/src/utils/path_utils.cpp @@ -447,6 +447,8 @@ std::vector splineTwoPoints( std::vector base_s, std::vector base_x, const double begin_diff, const double end_diff, std::vector new_s) { + assert(base_s.size() == 2 && base_x.size() == 2); + const double h = base_s.at(1) - base_s.at(0); const double c = begin_diff; @@ -643,15 +645,12 @@ BehaviorModuleOutput createGoalAroundPath(const std::shared_ptrprev_modified_goal; const Pose goal_pose = modified_goal ? modified_goal->pose : route_handler->getGoalPose(); - const auto shoulder_lanes = route_handler->getShoulderLanelets(); lanelet::ConstLanelet goal_lane; - const bool is_failed_getting_lanelet = std::invoke([&]() { - if (isInLanelets(goal_pose, shoulder_lanes)) { - return !lanelet::utils::query::getClosestLanelet(shoulder_lanes, goal_pose, &goal_lane); - } - return !route_handler->getGoalLanelet(&goal_lane); - }); + const auto shoulder_goal_lanes = route_handler->getShoulderLaneletsAtPose(goal_pose); + if (!shoulder_goal_lanes.empty()) goal_lane = shoulder_goal_lanes.front(); + const auto is_failed_getting_lanelet = + shoulder_goal_lanes.empty() && !route_handler->getGoalLanelet(&goal_lane); if (is_failed_getting_lanelet) { return output; } diff --git a/planning/behavior_path_planner_common/src/utils/utils.cpp b/planning/behavior_path_planner_common/src/utils/utils.cpp index e2a0db1c3f75f..d674f7770ac67 100644 --- a/planning/behavior_path_planner_common/src/utils/utils.cpp +++ b/planning/behavior_path_planner_common/src/utils/utils.cpp @@ -496,15 +496,12 @@ bool isEgoOutOfRoute( const Pose & goal_pose = (modified_goal && modified_goal->uuid == route_handler->getRouteUuid()) ? modified_goal->pose : route_handler->getGoalPose(); - const auto shoulder_lanes = route_handler->getShoulderLanelets(); lanelet::ConstLanelet goal_lane; - const bool is_failed_getting_lanelet = std::invoke([&]() { - if (utils::isInLanelets(goal_pose, shoulder_lanes)) { - return !lanelet::utils::query::getClosestLanelet(shoulder_lanes, goal_pose, &goal_lane); - } - return !route_handler->getGoalLanelet(&goal_lane); - }); + const auto shoulder_goal_lanes = route_handler->getShoulderLaneletsAtPose(goal_pose); + if (!shoulder_goal_lanes.empty()) goal_lane = shoulder_goal_lanes.front(); + const auto is_failed_getting_lanelet = + shoulder_goal_lanes.empty() && !route_handler->getGoalLanelet(&goal_lane); if (is_failed_getting_lanelet) { RCLCPP_WARN_STREAM( rclcpp::get_logger("behavior_path_planner").get_child("util"), "cannot find goal lanelet"); @@ -527,14 +524,7 @@ bool isEgoOutOfRoute( // If ego vehicle is out of the closest lanelet, return true // Check if ego vehicle is in shoulder lane - const bool is_in_shoulder_lane = std::invoke([&]() { - lanelet::Lanelet closest_shoulder_lanelet; - if (!lanelet::utils::query::getClosestLanelet( - shoulder_lanes, self_pose, &closest_shoulder_lanelet)) { - return false; - } - return lanelet::utils::isInLanelet(self_pose, closest_shoulder_lanelet); - }); + const bool is_in_shoulder_lane = !route_handler->getShoulderLaneletsAtPose(self_pose).empty(); // Check if ego vehicle is in road lane const bool is_in_road_lane = std::invoke([&]() { lanelet::ConstLanelet closest_road_lane; @@ -1513,8 +1503,7 @@ lanelet::ConstLanelets getExtendedCurrentLanesFromPath( return lanes; } -// TODO(Azu): In the future, get back lanelet within `to_back_dist` [m] from queried lane -lanelet::ConstLanelets getBackwardLanelets( +std::vector getPrecedingLanelets( const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanes, const Pose & current_pose, const double backward_length) { @@ -1529,18 +1518,21 @@ lanelet::ConstLanelets getBackwardLanelets( } const auto & front_lane = target_lanes.front(); - const auto preceding_lanes = route_handler.getPrecedingLaneletSequence( + return route_handler.getPrecedingLaneletSequence( front_lane, std::abs(backward_length - arc_length.length), {front_lane}); +} - lanelet::ConstLanelets backward_lanes{}; - const auto num_of_lanes = std::invoke([&preceding_lanes]() { - size_t sum{0}; - for (const auto & lanes : preceding_lanes) { - sum += lanes.size(); - } - return sum; - }); +lanelet::ConstLanelets getBackwardLanelets( + const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanes, + const Pose & current_pose, const double backward_length) +{ + const auto preceding_lanes = + getPrecedingLanelets(route_handler, target_lanes, current_pose, backward_length); + const auto calc_sum = [](size_t sum, const auto & lanes) { return sum + lanes.size(); }; + const auto num_of_lanes = + std::accumulate(preceding_lanes.begin(), preceding_lanes.end(), 0u, calc_sum); + lanelet::ConstLanelets backward_lanes{}; backward_lanes.reserve(num_of_lanes); for (const auto & lanes : preceding_lanes) { @@ -1660,13 +1652,6 @@ bool isAllowedGoalModification(const std::shared_ptr & route_handl bool checkOriginalGoalIsInShoulder(const std::shared_ptr & route_handler) { const Pose & goal_pose = route_handler->getOriginalGoalPose(); - const auto shoulder_lanes = route_handler->getShoulderLanelets(); - - lanelet::ConstLanelet closest_shoulder_lane{}; - if (lanelet::utils::query::getClosestLanelet(shoulder_lanes, goal_pose, &closest_shoulder_lane)) { - return lanelet::utils::isInLanelet(goal_pose, closest_shoulder_lane, 0.1); - } - - return false; + return !route_handler->getShoulderLaneletsAtPose(goal_pose).empty(); } } // namespace behavior_path_planner::utils 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_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/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); } { 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_path_start_planner_module/README.md b/planning/behavior_path_start_planner_module/README.md index ff0550e4d4867..ab2f0460b3fcb 100644 --- a/planning/behavior_path_start_planner_module/README.md +++ b/planning/behavior_path_start_planner_module/README.md @@ -91,36 +91,66 @@ The `StartPlannerModule` is designed to initiate its execution based on specific ### **End Conditions** -The `StartPlannerModule` terminates if the pull out / freespace maneuver has been completed. The `canTransitSuccessState` function assesses these conditions to decide if the module should terminate its execution. +The `StartPlannerModule` terminates when specific conditions are met, depending on the type of planner being used. The `canTransitSuccessState` function determines whether the module should transition to the success state based on the following criteria: -```plantuml -@startuml -start -:Start hasFinishedPullOut(); +#### When the Freespace Planner is active -if (status_.driving_forward && status_.found_pull_out_path) then (yes) +- If the end point of the freespace path is reached, the module transitions to the success state. - if (status_.planner_type == FREESPACE) then (yes) - :Calculate distance\nto pull_out_path.end_pose; - if (distance < th_arrived_distance) then (yes) - :return true;\n(Terminate module); - else (no) - :return false;\n(Continue running); - endif - else (no) - :Calculate arclength for\ncurrent_pose and pull_out_path.end_pose; - if (arclength_current - arclength_pull_out_end > offset) then (yes) - :return true;\n(Terminate module); - else (no) - :return false;\n(Continue running); - endif - endif +#### When any other type of planner is active + +The transition to the success state is determined by the following conditions: + +- If a reverse path is being generated or the search for a pull out path fails: + - The module does not transition to the success state. +- If the end point of the pull out path's shift section is reached: + - The module transitions to the success state. + +The flowchart below illustrates the decision-making process in the `canTransitSuccessState` function: +```plantuml +@startuml +@startuml +skinparam ActivityBackgroundColor #white +skinparam ActivityBorderColor #black +skinparam ActivityBorderThickness 1 +skinparam ActivityArrowColor #black +skinparam ActivityArrowThickness 1 +skinparam ActivityStartColor #black +skinparam ActivityEndColor #black +skinparam ActivityDiamondBackgroundColor #white +skinparam ActivityDiamondBorderColor #black +skinparam ActivityDiamondFontColor #black +partition canTransitSuccessState() { +start +if (planner type is FREESPACE?) then (yes) +if (Has reached freespace end?) then (yes) +#FF006C:true; +stop else (no) - :return false;\n(Continue running); +:false; +stop endif - +else (no) +if (driving is forward?) then (yes) +if (pull out path is found?) then (yes) +if (Has reached pull out end?) then (yes) +#FF006C:true; stop +else (no) +:false; +stop +endif +else (no) +:false; +stop +endif +else (no) +:false; +stop +endif +endif +} @enduml ``` @@ -464,14 +494,15 @@ See also [[1]](https://www.sciencedirect.com/science/article/pii/S14746670153474 #### parameters for geometric pull out -| Name | Unit | Type | Description | Default value | -| :-------------------------- | :---- | :----- | :-------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ | -| enable_geometric_pull_out | [-] | bool | flag whether to enable geometric pull out | true | -| divide_pull_out_path | [-] | bool | flag whether to divide arc paths. The path is assumed to be divided because the curvature is not continuous. But it requires a stop during the departure. | false | -| geometric_pull_out_velocity | [m/s] | double | velocity of geometric pull out | 1.0 | -| arc_path_interval | [m] | double | path points interval of arc paths of geometric pull out | 1.0 | -| lane_departure_margin | [m] | double | margin of deviation to lane right | 0.2 | -| pull_out_max_steer_angle | [rad] | double | maximum steer angle for path generation | 0.26 | +| Name | Unit | Type | Description | Default value | +| :------------------------------------ | :---- | :----- | :-------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ | +| enable_geometric_pull_out | [-] | bool | flag whether to enable geometric pull out | true | +| divide_pull_out_path | [-] | bool | flag whether to divide arc paths. The path is assumed to be divided because the curvature is not continuous. But it requires a stop during the departure. | false | +| geometric_pull_out_velocity | [m/s] | double | velocity of geometric pull out | 1.0 | +| arc_path_interval | [m] | double | path points interval of arc paths of geometric pull out | 1.0 | +| lane_departure_margin | [m] | double | margin of deviation to lane right | 0.2 | +| lane_departure_check_expansion_margin | [m] | double | margin to expand the ego vehicle footprint when doing lane departure checks | 0.0 | +| pull_out_max_steer_angle | [rad] | double | maximum steer angle for path generation | 0.26 | ## **backward pull out start point search** diff --git a/planning/behavior_path_start_planner_module/config/start_planner.param.yaml b/planning/behavior_path_start_planner_module/config/start_planner.param.yaml index 46469de68149e..7de76c28cef5c 100644 --- a/planning/behavior_path_start_planner_module/config/start_planner.param.yaml +++ b/planning/behavior_path_start_planner_module/config/start_planner.param.yaml @@ -40,6 +40,7 @@ geometric_pull_out_velocity: 1.0 arc_path_interval: 1.0 lane_departure_margin: 0.2 + lane_departure_check_expansion_margin: 0.0 backward_velocity: -1.0 pull_out_max_steer_angle: 0.26 # 15deg # search start pose backward diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/data_structs.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/data_structs.hpp index 0e85c1d0e76b3..04248ee7bd5fb 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/data_structs.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/data_structs.hpp @@ -71,6 +71,7 @@ struct StartPlannerParameters behavior_path_planner::utils::path_safety_checker::ObjectTypesToCheck object_types_to_check_for_path_generation{}; double center_line_path_interval{0.0}; + double lane_departure_check_expansion_margin{0.0}; // shift pull out bool enable_shift_pull_out{false}; 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 3089134a16500..9a2749759d03e 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 @@ -79,7 +79,9 @@ class PullOutPlannerBase *dynamic_objects, parameters_.th_moving_object_velocity); auto [pull_out_lane_stop_objects, others] = utils::path_safety_checker::separateObjectsByLanelets( - stop_objects, pull_out_lanes, utils::path_safety_checker::isPolygonOverlapLanelet); + stop_objects, pull_out_lanes, [](const auto & obj, const auto & lane) { + return utils::path_safety_checker::isPolygonOverlapLanelet(obj, lane); + }); utils::path_safety_checker::filterObjectsByClass( pull_out_lane_stop_objects, parameters_.object_types_to_check_for_path_generation); 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..ea5afb133d57f 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() {} }; @@ -304,7 +306,8 @@ class StartPlannerModule : public SceneModuleInterface const double velocity_threshold, const double object_check_backward_distance, const double object_check_forward_distance) const; bool needToPrepareBlinkerBeforeStartDrivingForward() const; - bool hasFinishedPullOut() const; + bool hasReachedFreespaceEnd() const; + bool hasReachedPullOutEnd() const; bool hasFinishedBackwardDriving() const; bool hasCollisionWithDynamicObjects() const; bool isStopped(); diff --git a/planning/behavior_path_start_planner_module/src/manager.cpp b/planning/behavior_path_start_planner_module/src/manager.cpp index 794577d7cc7aa..d5731f54224b6 100644 --- a/planning/behavior_path_start_planner_module/src/manager.cpp +++ b/planning/behavior_path_start_planner_module/src/manager.cpp @@ -101,6 +101,8 @@ void StartPlannerModuleManager::init(rclcpp::Node * node) node->declare_parameter(ns + "arc_path_interval"); p.parallel_parking_parameters.pull_out_lane_departure_margin = node->declare_parameter(ns + "lane_departure_margin"); + p.lane_departure_check_expansion_margin = + node->declare_parameter(ns + "lane_departure_check_expansion_margin"); p.parallel_parking_parameters.pull_out_max_steer_angle = node->declare_parameter(ns + "pull_out_max_steer_angle"); // 15deg p.parallel_parking_parameters.center_line_path_interval = @@ -435,6 +437,9 @@ void StartPlannerModuleManager::updateModuleParams( updateParam( parameters, ns + "lane_departure_margin", p->parallel_parking_parameters.pull_out_lane_departure_margin); + updateParam( + parameters, ns + "lane_departure_check_expansion_margin", + p->lane_departure_check_expansion_margin); updateParam( parameters, ns + "pull_out_max_steer_angle", p->parallel_parking_parameters.pull_out_max_steer_angle); 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 be6b6acef64bd..7e1f38f30c378 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 @@ -65,6 +65,11 @@ StartPlannerModule::StartPlannerModule( { lane_departure_checker_ = std::make_shared(); lane_departure_checker_->setVehicleInfo(vehicle_info_); + lane_departure_checker::Param lane_departure_checker_params; + lane_departure_checker_params.footprint_extra_margin = + parameters->lane_departure_check_expansion_margin; + + lane_departure_checker_->setParam(lane_departure_checker_params); // set enabled planner if (parameters_->enable_shift_pull_out) { @@ -247,6 +252,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(); @@ -398,11 +410,13 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const auto get_gap_between_ego_and_lane_border = [&]( geometry_msgs::msg::Pose & ego_overhang_point_as_pose, - const bool ego_is_merging_from_the_left) -> std::optional { + const bool ego_is_merging_from_the_left) -> std::optional> { const auto local_vehicle_footprint = vehicle_info_.createFootprint(); const auto vehicle_footprint = transformVector(local_vehicle_footprint, tier4_autoware_utils::pose2transform(current_pose)); double smallest_lateral_gap_between_ego_and_border = std::numeric_limits::max(); + double corresponding_lateral_gap_with_other_lane_bound = std::numeric_limits::max(); + for (const auto & point : vehicle_footprint) { geometry_msgs::msg::Pose point_pose; point_pose.position.x = point.x(); @@ -413,9 +427,12 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const lanelet::utils::query::getClosestLanelet(target_lanes, point_pose, &closest_lanelet); lanelet::ConstLanelet closest_lanelet_const(closest_lanelet.constData()); - const lanelet::ConstLineString2d current_lane_bound = (ego_is_merging_from_the_left) - ? closest_lanelet_const.rightBound2d() - : closest_lanelet_const.leftBound2d(); + const auto [current_lane_bound, other_side_lane_bound] = + (ego_is_merging_from_the_left) + ? std::make_pair( + closest_lanelet_const.rightBound2d(), closest_lanelet_const.leftBound2d()) + : std::make_pair( + closest_lanelet_const.leftBound2d(), closest_lanelet_const.rightBound2d()); const double current_point_lateral_gap = calc_absolute_lateral_offset(current_lane_bound, point_pose); if (current_point_lateral_gap < smallest_lateral_gap_between_ego_and_border) { @@ -423,19 +440,35 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const ego_overhang_point_as_pose.position.x = point.x(); ego_overhang_point_as_pose.position.y = point.y(); ego_overhang_point_as_pose.position.z = 0.0; + corresponding_lateral_gap_with_other_lane_bound = + calc_absolute_lateral_offset(other_side_lane_bound, point_pose); } } + if (smallest_lateral_gap_between_ego_and_border == std::numeric_limits::max()) { return std::nullopt; } - return smallest_lateral_gap_between_ego_and_border; + return std::make_pair( + (smallest_lateral_gap_between_ego_and_border), + (corresponding_lateral_gap_with_other_lane_bound)); }; geometry_msgs::msg::Pose ego_overhang_point_as_pose; - const auto gap_between_ego_and_lane_border = + const auto gaps_with_lane_borders_pair = get_gap_between_ego_and_lane_border(ego_overhang_point_as_pose, ego_is_merging_from_the_left); - if (!gap_between_ego_and_lane_border) return false; + if (!gaps_with_lane_borders_pair.has_value()) { + return false; + } + + const auto & gap_between_ego_and_lane_border = gaps_with_lane_borders_pair.value().first; + const auto & corresponding_lateral_gap_with_other_lane_bound = + gaps_with_lane_borders_pair.value().second; + + // middle of the lane is crossed, no need to check for collisions anymore + if (gap_between_ego_and_lane_border < corresponding_lateral_gap_with_other_lane_bound) { + return true; + } // Get the lanelets that will be queried for target objects const auto relevant_lanelets = std::invoke([&]() -> std::optional { lanelet::Lanelet closest_lanelet; @@ -485,7 +518,7 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const if (!closest_object_width) return false; // Decide if the closest object does not fit in the gap left by the ego vehicle. return closest_object_width.value() + parameters_->extra_width_margin_for_rear_obstacle > - gap_between_ego_and_lane_border.value(); + gap_between_ego_and_lane_border; } bool StartPlannerModule::isCloseToOriginalStartPose() const @@ -551,7 +584,35 @@ bool StartPlannerModule::isExecutionReady() const bool StartPlannerModule::canTransitSuccessState() { - return hasFinishedPullOut(); + // Freespace Planner: + // - Can transit to success if the goal position is reached. + // - Cannot transit to success if the goal position is not reached. + if (status_.planner_type == PlannerType::FREESPACE) { + if (hasReachedFreespaceEnd()) { + RCLCPP_DEBUG( + getLogger(), "Transit to success: Freespace planner reached the end point of the path."); + return true; + } + return false; + } + + // Other Planners: + // - Cannot transit to success if the vehicle is driving in reverse. + // - Cannot transit to success if a safe path cannot be found due to: + // - Insufficient margin against static objects. + // - No path found that stays within the lane. + // In such cases, a stop point needs to be embedded and keep running start_planner. + // - Can transit to success if the end point of the pullout path is reached. + if (!status_.driving_forward || !status_.found_pull_out_path) { + return false; + } + + if (hasReachedPullOutEnd()) { + RCLCPP_DEBUG(getLogger(), "Transit to success: Reached the end point of the pullout path."); + return true; + } + + return false; } BehaviorModuleOutput StartPlannerModule::plan() @@ -1135,7 +1196,9 @@ PredictedObjects StartPlannerModule::filterStopObjectsInPullOutLanes( // filter for objects located in pull out lanes and moving at a speed below the threshold auto [stop_objects_in_pull_out_lanes, others] = utils::path_safety_checker::separateObjectsByLanelets( - stop_objects, pull_out_lanes, utils::path_safety_checker::isPolygonOverlapLanelet); + stop_objects, pull_out_lanes, [](const auto & obj, const auto & lane) { + return utils::path_safety_checker::isPolygonOverlapLanelet(obj, lane); + }); const auto path = planner_data_->route_handler->getCenterLinePath( pull_out_lanes, object_check_backward_distance, object_check_forward_distance); @@ -1150,17 +1213,16 @@ PredictedObjects StartPlannerModule::filterStopObjectsInPullOutLanes( return stop_objects_in_pull_out_lanes; } -bool StartPlannerModule::hasFinishedPullOut() const +bool StartPlannerModule::hasReachedFreespaceEnd() const { - if (!status_.driving_forward || !status_.found_pull_out_path) { - return false; - } + const auto & current_pose = planner_data_->self_odometry->pose.pose; + return tier4_autoware_utils::calcDistance2d(current_pose, status_.pull_out_path.end_pose) < + parameters_->th_arrived_distance; +} +bool StartPlannerModule::hasReachedPullOutEnd() const +{ const auto current_pose = planner_data_->self_odometry->pose.pose; - if (status_.planner_type == PlannerType::FREESPACE) { - return tier4_autoware_utils::calcDistance2d(current_pose, status_.pull_out_path.end_pose) < - parameters_->th_arrived_distance; - } // check that ego has passed pull out end point const double backward_path_length = @@ -1175,9 +1237,8 @@ bool StartPlannerModule::hasFinishedPullOut() const // offset to not finish the module before engage constexpr double offset = 0.1; - const bool has_finished = arclength_current.length - arclength_pull_out_end.length > offset; - return has_finished; + return arclength_current.length - arclength_pull_out_end.length > offset; } bool StartPlannerModule::needToPrepareBlinkerBeforeStartDrivingForward() const @@ -1242,8 +1303,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; } @@ -1254,6 +1317,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); diff --git a/planning/behavior_path_start_planner_module/src/util.cpp b/planning/behavior_path_start_planner_module/src/util.cpp index 82e9d1a08e816..4ed499826dbd1 100644 --- a/planning/behavior_path_start_planner_module/src/util.cpp +++ b/planning/behavior_path_start_planner_module/src/util.cpp @@ -90,11 +90,10 @@ lanelet::ConstLanelets getPullOutLanes( const auto & route_handler = planner_data->route_handler; const auto start_pose = planner_data->route_handler->getOriginalStartPose(); - lanelet::ConstLanelet current_shoulder_lane; - if (route_handler->getPullOutStartLane( - route_handler->getShoulderLanelets(), start_pose, vehicle_width, ¤t_shoulder_lane)) { + const auto current_shoulder_lane = route_handler->getPullOutStartLane(start_pose, vehicle_width); + if (current_shoulder_lane) { // pull out from shoulder lane - return route_handler->getShoulderLaneletSequence(current_shoulder_lane, start_pose); + return route_handler->getShoulderLaneletSequence(*current_shoulder_lane, start_pose); } // pull out from road lane diff --git a/planning/behavior_velocity_blind_spot_module/CMakeLists.txt b/planning/behavior_velocity_blind_spot_module/CMakeLists.txt index 682da3ae58d7e..7ff2419eed919 100644 --- a/planning/behavior_velocity_blind_spot_module/CMakeLists.txt +++ b/planning/behavior_velocity_blind_spot_module/CMakeLists.txt @@ -3,12 +3,13 @@ project(behavior_velocity_blind_spot_module) find_package(autoware_cmake REQUIRED) autoware_package() -pluginlib_export_plugin_description_file(behavior_velocity_planner plugins.xml) +pluginlib_export_plugin_description_file(autoware_behavior_velocity_planner plugins.xml) ament_auto_add_library(${PROJECT_NAME} SHARED src/debug.cpp src/manager.cpp src/scene.cpp + src/decisions.cpp ) ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_velocity_blind_spot_module/config/blind_spot.param.yaml b/planning/behavior_velocity_blind_spot_module/config/blind_spot.param.yaml index 3c22d1fe65db5..d7131d8c19245 100644 --- a/planning/behavior_velocity_blind_spot_module/config/blind_spot.param.yaml +++ b/planning/behavior_velocity_blind_spot_module/config/blind_spot.param.yaml @@ -3,10 +3,12 @@ blind_spot: use_pass_judge_line: true stop_line_margin: 1.0 # [m] - backward_length: 50.0 # [m] + backward_detection_length: 100.0 # [m] ignore_width_from_center_line: 0.7 # [m] - max_future_movement_time: 10.0 # [second] - threshold_yaw_diff: 0.523 # [rad] adjacent_extend_width: 1.5 # [m] opposite_adjacent_extend_width: 1.5 # [m] + max_future_movement_time: 10.0 # [second] + ttc_min: -5.0 # [s] + ttc_max: 5.0 # [s] + ttc_ego_minimal_velocity: 5.0 # [m/s] enable_rtc: false # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval diff --git a/planning/behavior_velocity_blind_spot_module/src/debug.cpp b/planning/behavior_velocity_blind_spot_module/src/debug.cpp index 5cc90afb0043d..a30836ab9f6a9 100644 --- a/planning/behavior_velocity_blind_spot_module/src/debug.cpp +++ b/planning/behavior_velocity_blind_spot_module/src/debug.cpp @@ -71,55 +71,16 @@ visualization_msgs::msg::MarkerArray createLaneletPolygonsMarkerArray( return msg; } -visualization_msgs::msg::MarkerArray createPoseMarkerArray( - const geometry_msgs::msg::Pose & pose, const StateMachine::State & state, const std::string & ns, - const int64_t id, const double r, const double g, const double b) -{ - visualization_msgs::msg::MarkerArray msg; - - if (state == StateMachine::State::STOP) { - visualization_msgs::msg::Marker marker_line{}; - marker_line.header.frame_id = "map"; - marker_line.ns = ns + "_line"; - marker_line.id = id; - marker_line.lifetime = rclcpp::Duration::from_seconds(0.3); - marker_line.type = visualization_msgs::msg::Marker::LINE_STRIP; - marker_line.action = visualization_msgs::msg::Marker::ADD; - marker_line.pose.orientation = createMarkerOrientation(0, 0, 0, 1.0); - marker_line.scale = createMarkerScale(0.1, 0.0, 0.0); - marker_line.color = createMarkerColor(r, g, b, 0.999); - - const double yaw = tf2::getYaw(pose.orientation); - - const double a = 3.0; - geometry_msgs::msg::Point p0; - p0.x = pose.position.x - a * std::sin(yaw); - p0.y = pose.position.y + a * std::cos(yaw); - p0.z = pose.position.z; - marker_line.points.push_back(p0); - - geometry_msgs::msg::Point p1; - p1.x = pose.position.x + a * std::sin(yaw); - p1.y = pose.position.y - a * std::cos(yaw); - p1.z = pose.position.z; - marker_line.points.push_back(p1); - - msg.markers.push_back(marker_line); - } - - return msg; -} - } // namespace motion_utils::VirtualWalls BlindSpotModule::createVirtualWalls() { motion_utils::VirtualWalls virtual_walls; - if (!isActivated() && !is_over_pass_judge_line_) { + if (debug_data_.virtual_wall_pose) { motion_utils::VirtualWall wall; wall.text = "blind_spot"; - wall.pose = debug_data_.virtual_wall_pose; + wall.pose = debug_data_.virtual_wall_pose.value(); wall.ns = std::to_string(module_id_) + "_"; virtual_walls.push_back(wall); } @@ -130,28 +91,14 @@ visualization_msgs::msg::MarkerArray BlindSpotModule::createDebugMarkerArray() { visualization_msgs::msg::MarkerArray debug_marker_array; - const auto state = state_machine_.getState(); const auto now = this->clock_->now(); - appendMarkerArray( - createPoseMarkerArray( - debug_data_.stop_point_pose, state, "stop_point_pose", module_id_, 1.0, 0.0, 0.0), - &debug_marker_array, now); - - appendMarkerArray( - createPoseMarkerArray( - debug_data_.judge_point_pose, state, "judge_point_pose", module_id_, 1.0, 1.0, 0.5), - &debug_marker_array, now); - - appendMarkerArray( - createLaneletPolygonsMarkerArray( - debug_data_.conflict_areas, "conflict_area", module_id_, 0.0, 0.5, 0.5), - &debug_marker_array, now); - - appendMarkerArray( - createLaneletPolygonsMarkerArray( - debug_data_.detection_areas, "detection_area", module_id_, 0.5, 0.0, 0.0), - &debug_marker_array, now); + if (debug_data_.detection_area) { + appendMarkerArray( + createLaneletPolygonsMarkerArray( + {debug_data_.detection_area.value()}, "detection_area", module_id_, 0.5, 0.0, 0.0), + &debug_marker_array, now); + } appendMarkerArray( debug::createObjectsMarkerArray( diff --git a/planning/behavior_velocity_blind_spot_module/src/decisions.cpp b/planning/behavior_velocity_blind_spot_module/src/decisions.cpp new file mode 100644 index 0000000000000..d3e439b3663f8 --- /dev/null +++ b/planning/behavior_velocity_blind_spot_module/src/decisions.cpp @@ -0,0 +1,154 @@ +// 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 "scene.hpp" + +#include + +namespace behavior_velocity_planner +{ + +/* + * for default + */ +template +void BlindSpotModule::setRTCStatusByDecision( + const T &, const autoware_auto_planning_msgs::msg::PathWithLaneId & path) +{ + static_assert("Unsupported type passed to setRTCStatus"); + return; +} + +template +void BlindSpotModule::reactRTCApprovalByDecision( + [[maybe_unused]] const T & decision, + [[maybe_unused]] autoware_auto_planning_msgs::msg::PathWithLaneId * path, + [[maybe_unused]] StopReason * stop_reason) +{ + static_assert("Unsupported type passed to reactRTCApprovalByDecision"); +} + +/* + * for InternalError + */ +template <> +void BlindSpotModule::setRTCStatusByDecision( + [[maybe_unused]] const InternalError & decision, + [[maybe_unused]] const autoware_auto_planning_msgs::msg::PathWithLaneId & path) +{ + return; +} + +template <> +void BlindSpotModule::reactRTCApprovalByDecision( + [[maybe_unused]] const InternalError & decision, + [[maybe_unused]] autoware_auto_planning_msgs::msg::PathWithLaneId * path, + [[maybe_unused]] StopReason * stop_reason) +{ + return; +} + +/* + * For OverPassJudge + */ +template <> +void BlindSpotModule::setRTCStatusByDecision( + [[maybe_unused]] const OverPassJudge & decision, + [[maybe_unused]] const autoware_auto_planning_msgs::msg::PathWithLaneId & path) +{ + return; +} + +template <> +void BlindSpotModule::reactRTCApprovalByDecision( + [[maybe_unused]] const OverPassJudge & decision, + [[maybe_unused]] autoware_auto_planning_msgs::msg::PathWithLaneId * path, + [[maybe_unused]] StopReason * stop_reason) +{ + return; +} + +/* + * for Unsafe + */ +template <> +void BlindSpotModule::setRTCStatusByDecision( + const Unsafe & decision, const autoware_auto_planning_msgs::msg::PathWithLaneId & path) +{ + setSafe(false); + const auto & current_pose = planner_data_->current_odometry->pose; + setDistance( + motion_utils::calcSignedArcLength(path.points, current_pose.position, decision.stop_line_idx)); + return; +} + +template <> +void BlindSpotModule::reactRTCApprovalByDecision( + const Unsafe & decision, autoware_auto_planning_msgs::msg::PathWithLaneId * path, + StopReason * stop_reason) +{ + if (!isActivated()) { + constexpr double stop_vel = 0.0; + planning_utils::setVelocityFromIndex(decision.stop_line_idx, stop_vel, path); + debug_data_.virtual_wall_pose = planning_utils::getAheadPose( + decision.stop_line_idx, planner_data_->vehicle_info_.max_longitudinal_offset_m, *path); + + tier4_planning_msgs::msg::StopFactor stop_factor; + const auto stop_pose = path->points.at(decision.stop_line_idx).point.pose; + stop_factor.stop_pose = stop_pose; + stop_factor.stop_factor_points = planning_utils::toRosPoints(debug_data_.conflicting_targets); + planning_utils::appendStopReason(stop_factor, stop_reason); + velocity_factor_.set( + path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::UNKNOWN); + } + return; +} + +/* + * for Safe + */ +template <> +void BlindSpotModule::setRTCStatusByDecision( + const Safe & decision, const autoware_auto_planning_msgs::msg::PathWithLaneId & path) +{ + setSafe(true); + const auto & current_pose = planner_data_->current_odometry->pose; + setDistance( + motion_utils::calcSignedArcLength(path.points, current_pose.position, decision.stop_line_idx)); + return; +} + +template <> +void BlindSpotModule::reactRTCApprovalByDecision( + const Safe & decision, autoware_auto_planning_msgs::msg::PathWithLaneId * path, + StopReason * stop_reason) +{ + if (!isActivated()) { + constexpr double stop_vel = 0.0; + planning_utils::setVelocityFromIndex(decision.stop_line_idx, stop_vel, path); + debug_data_.virtual_wall_pose = planning_utils::getAheadPose( + decision.stop_line_idx, planner_data_->vehicle_info_.max_longitudinal_offset_m, *path); + + tier4_planning_msgs::msg::StopFactor stop_factor; + const auto stop_pose = path->points.at(decision.stop_line_idx).point.pose; + stop_factor.stop_pose = stop_pose; + stop_factor.stop_factor_points = planning_utils::toRosPoints(debug_data_.conflicting_targets); + planning_utils::appendStopReason(stop_factor, stop_reason); + velocity_factor_.set( + path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::UNKNOWN); + } + return; +} + +} // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_blind_spot_module/src/manager.cpp b/planning/behavior_velocity_blind_spot_module/src/manager.cpp index d114ab0c65da9..07742a1217ab3 100644 --- a/planning/behavior_velocity_blind_spot_module/src/manager.cpp +++ b/planning/behavior_velocity_blind_spot_module/src/manager.cpp @@ -36,17 +36,20 @@ BlindSpotModuleManager::BlindSpotModuleManager(rclcpp::Node & node) planner_param_.use_pass_judge_line = getOrDeclareParameter(node, ns + ".use_pass_judge_line"); planner_param_.stop_line_margin = getOrDeclareParameter(node, ns + ".stop_line_margin"); - planner_param_.backward_length = getOrDeclareParameter(node, ns + ".backward_length"); + planner_param_.backward_detection_length = + getOrDeclareParameter(node, ns + ".backward_detection_length"); planner_param_.ignore_width_from_center_line = getOrDeclareParameter(node, ns + ".ignore_width_from_center_line"); - planner_param_.max_future_movement_time = - getOrDeclareParameter(node, ns + ".max_future_movement_time"); - planner_param_.threshold_yaw_diff = - getOrDeclareParameter(node, ns + ".threshold_yaw_diff"); planner_param_.adjacent_extend_width = getOrDeclareParameter(node, ns + ".adjacent_extend_width"); planner_param_.opposite_adjacent_extend_width = getOrDeclareParameter(node, ns + ".opposite_adjacent_extend_width"); + planner_param_.max_future_movement_time = + getOrDeclareParameter(node, ns + ".max_future_movement_time"); + planner_param_.ttc_min = getOrDeclareParameter(node, ns + ".ttc_min"); + planner_param_.ttc_max = getOrDeclareParameter(node, ns + ".ttc_max"); + planner_param_.ttc_ego_minimal_velocity = + getOrDeclareParameter(node, ns + ".ttc_ego_minimal_velocity"); } void BlindSpotModuleManager::launchNewModules( @@ -63,17 +66,21 @@ void BlindSpotModuleManager::launchNewModules( } // Is turning lane? - const std::string turn_direction = ll.attributeOr("turn_direction", "else"); - if (turn_direction != "left" && turn_direction != "right") { + const std::string turn_direction_str = ll.attributeOr("turn_direction", "else"); + if (turn_direction_str != "left" && turn_direction_str != "right") { continue; } + const auto turn_direction = turn_direction_str == "left" + ? BlindSpotModule::TurnDirection::LEFT + : BlindSpotModule::TurnDirection::RIGHT; registerModule(std::make_shared( - module_id, lane_id, planner_data_, planner_param_, logger_.get_child("blind_spot_module"), - clock_)); + module_id, lane_id, turn_direction, planner_data_, planner_param_, + logger_.get_child("blind_spot_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_blind_spot_module/src/scene.cpp b/planning/behavior_velocity_blind_spot_module/src/scene.cpp index 7a3ea3160cb24..6c7c12b556581 100644 --- a/planning/behavior_velocity_blind_spot_module/src/scene.cpp +++ b/planning/behavior_velocity_blind_spot_module/src/scene.cpp @@ -44,165 +44,143 @@ namespace behavior_velocity_planner { namespace bg = boost::geometry; -namespace -{ -[[maybe_unused]] geometry_msgs::msg::Polygon toGeomPoly(const lanelet::CompoundPolygon3d & poly) -{ - geometry_msgs::msg::Polygon geom_poly; - - for (const auto & p : poly) { - geometry_msgs::msg::Point32 geom_point; - geom_point.x = p.x(); - geom_point.y = p.y(); - geom_point.z = p.z(); - geom_poly.points.push_back(geom_point); - } - - return geom_poly; -} -} // namespace - BlindSpotModule::BlindSpotModule( - const int64_t module_id, const int64_t lane_id, std::shared_ptr planner_data, - const PlannerParam & planner_param, const rclcpp::Logger logger, - const rclcpp::Clock::SharedPtr clock) + const int64_t module_id, const int64_t lane_id, const TurnDirection turn_direction, + const std::shared_ptr planner_data, const PlannerParam & planner_param, + const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock) : SceneModuleInterface(module_id, logger, clock), lane_id_(lane_id), planner_param_{planner_param}, - turn_direction_(TurnDirection::INVALID), + turn_direction_(turn_direction), is_over_pass_judge_line_(false) { velocity_factor_.init(PlanningBehavior::REAR_CHECK); - - const auto & assigned_lanelet = - planner_data->route_handler_->getLaneletMapPtr()->laneletLayer.get(lane_id); - const std::string turn_direction = assigned_lanelet.attributeOr("turn_direction", "else"); - if (!turn_direction.compare("left")) { - turn_direction_ = TurnDirection::LEFT; - } else if (!turn_direction.compare("right")) { - turn_direction_ = TurnDirection::RIGHT; - } + sibling_straight_lanelet_ = getSiblingStraightLanelet(planner_data); } -bool BlindSpotModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) +void BlindSpotModule::initializeRTCStatus() { - debug_data_ = DebugData(); - *stop_reason = planning_utils::initializeStopReason(StopReason::BLIND_SPOT); - - const auto input_path = *path; - - const auto current_state = state_machine_.getState(); - RCLCPP_DEBUG( - logger_, "lane_id = %ld, state = %s", lane_id_, StateMachine::toString(current_state).c_str()); - - /* get current pose */ - const auto & current_pose = planner_data_->current_odometry->pose; + setSafe(true); + setDistance(std::numeric_limits::lowest()); +} - /* get lanelet map */ - const auto lanelet_map_ptr = planner_data_->route_handler_->getLaneletMapPtr(); - const auto routing_graph_ptr = planner_data_->route_handler_->getRoutingGraphPtr(); +BlindSpotDecision BlindSpotModule::modifyPathVelocityDetail( + PathWithLaneId * path, [[maybe_unused]] StopReason * stop_reason) +{ + if (planner_param_.use_pass_judge_line && is_over_pass_judge_line_) { + return OverPassJudge{"already over the pass judge line. no plan needed."}; + } + const auto & input_path = *path; /* set stop-line and stop-judgement-line for base_link */ const auto interpolated_path_info_opt = generateInterpolatedPathInfo(input_path); if (!interpolated_path_info_opt) { - RCLCPP_DEBUG(logger_, "[BlindSpotModule::run] failed to interpolate path"); - return false; + return InternalError{"Failed to interpolate path"}; } const auto & interpolated_path_info = interpolated_path_info_opt.value(); - if (!sibling_straight_lanelet_) { - sibling_straight_lanelet_ = getSiblingStraightLanelet(); - } - const auto stoplines_idx_opt = generateStopLine(interpolated_path_info, path); if (!stoplines_idx_opt) { - RCLCPP_DEBUG(logger_, "[BlindSpotModule::run] setStopLineIdx fail"); - return false; + return InternalError{"generateStopLine fail"}; } const auto [default_stopline_idx, critical_stopline_idx] = stoplines_idx_opt.value(); - - if (default_stopline_idx <= 0) { - RCLCPP_DEBUG( - logger_, "[Blind Spot] stop line or pass judge line is at path[0], ignore planning."); - *path = input_path; // reset path - setSafe(true); - setDistance(std::numeric_limits::lowest()); - return true; + if (default_stopline_idx == 0) { + return InternalError{"stop line or pass judge line is at path[0], ignore planning."}; } /* calc closest index */ + const auto & current_pose = planner_data_->current_odometry->pose; const auto closest_idx = motion_utils::findFirstNearestIndexWithSoftConstraints( input_path.points, current_pose, planner_data_->ego_nearest_dist_threshold, planner_data_->ego_nearest_yaw_threshold); const auto stop_line_idx = closest_idx > default_stopline_idx ? critical_stopline_idx : default_stopline_idx; - - /* set judge line dist */ - const double current_vel = planner_data_->current_velocity->twist.linear.x; - const double max_acc = planner_data_->max_stop_acceleration_threshold; - const double delay_response_time = planner_data_->delay_response_time; - const double pass_judge_line_dist = - planning_utils::calcJudgeLineDistWithAccLimit(current_vel, max_acc, delay_response_time); - const auto stop_point_pose = path->points.at(stop_line_idx).point.pose; - const auto ego_segment_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( - input_path.points, current_pose, planner_data_->ego_nearest_dist_threshold, - planner_data_->ego_nearest_yaw_threshold); - const size_t stop_point_segment_idx = - motion_utils::findNearestSegmentIndex(input_path.points, stop_point_pose.position); - const auto distance_until_stop = motion_utils::calcSignedArcLength( - input_path.points, current_pose.position, ego_segment_idx, stop_point_pose.position, - stop_point_segment_idx); - - /* get debug info */ const auto stop_line_pose = planning_utils::getAheadPose( - stop_line_idx, planner_data_->vehicle_info_.max_longitudinal_offset_m, *path); - debug_data_.virtual_wall_pose = stop_line_pose; - const auto stop_pose = path->points.at(stop_line_idx).point.pose; - debug_data_.stop_point_pose = stop_pose; + stop_line_idx, planner_data_->vehicle_info_.max_longitudinal_offset_m, input_path); - /* if current_state = GO, and current_pose is over judge_line, ignore planning. */ - if (planner_param_.use_pass_judge_line) { - const double eps = 1e-1; // to prevent hunting - if ( - current_state == StateMachine::State::GO && - distance_until_stop + eps < pass_judge_line_dist) { - RCLCPP_DEBUG(logger_, "over the pass judge line. no plan needed."); - *path = input_path; // reset path - setSafe(true); - setDistance(std::numeric_limits::lowest()); - return true; // no plan needed. + const auto is_over_pass_judge = isOverPassJudge(input_path, stop_line_pose); + if (is_over_pass_judge) { + is_over_pass_judge_line_ = true; + return is_over_pass_judge.value(); + } + + if (!blind_spot_lanelets_) { + const auto blind_spot_lanelets = generateBlindSpotLanelets(input_path); + if (!blind_spot_lanelets.empty()) { + blind_spot_lanelets_ = blind_spot_lanelets; } } + if (!blind_spot_lanelets_) { + return InternalError{"There are not blind_spot_lanelets"}; + } + const auto & blind_spot_lanelets = blind_spot_lanelets_.value(); - /* get dynamic object */ - const auto objects_ptr = planner_data_->predicted_objects; + const auto detection_area_opt = generateBlindSpotPolygons( + input_path, closest_idx, blind_spot_lanelets, + path->points.at(critical_stopline_idx).point.pose); + if (!detection_area_opt) { + return InternalError{"Failed to generate BlindSpotPolygons"}; + } + const auto & detection_area = detection_area_opt.value(); + debug_data_.detection_area = detection_area; + const auto ego_time_to_reach_stop_line = computeTimeToPassStopLine( + blind_spot_lanelets, path->points.at(critical_stopline_idx).point.pose); /* calculate dynamic collision around detection area */ - bool has_obstacle = checkObstacleInBlindSpot( - lanelet_map_ptr, routing_graph_ptr, *path, objects_ptr, closest_idx, stop_line_pose); + const auto collision_obstacle = isCollisionDetected( + blind_spot_lanelets, path->points.at(critical_stopline_idx).point.pose, detection_area, + ego_time_to_reach_stop_line); state_machine_.setStateWithMarginTime( - has_obstacle ? StateMachine::State::STOP : StateMachine::State::GO, + collision_obstacle.has_value() ? StateMachine::State::STOP : StateMachine::State::GO, logger_.get_child("state_machine"), *clock_); - /* set stop speed */ - setSafe(state_machine_.getState() != StateMachine::State::STOP); - setDistance(motion_utils::calcSignedArcLength( - path->points, current_pose.position, path->points.at(stop_line_idx).point.pose.position)); - if (!isActivated()) { - constexpr double stop_vel = 0.0; - planning_utils::setVelocityFromIndex(stop_line_idx, stop_vel, path); - - /* get stop point and stop factor */ - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = debug_data_.stop_point_pose; - stop_factor.stop_factor_points = planning_utils::toRosPoints(debug_data_.conflicting_targets); - planning_utils::appendStopReason(stop_factor, stop_reason); - velocity_factor_.set( - path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::UNKNOWN); - } else { - *path = input_path; // reset path + if (state_machine_.getState() == StateMachine::State::STOP) { + return Unsafe{stop_line_idx, collision_obstacle}; } + + return Safe{stop_line_idx}; +} + +// template-specification based visitor pattern +// https://en.cppreference.com/w/cpp/utility/variant/visit +template +struct VisitorSwitch : Ts... +{ + using Ts::operator()...; +}; +template +VisitorSwitch(Ts...) -> VisitorSwitch; + +void BlindSpotModule::setRTCStatus( + const BlindSpotDecision & decision, const autoware_auto_planning_msgs::msg::PathWithLaneId & path) +{ + std::visit( + VisitorSwitch{[&](const auto & sub_decision) { setRTCStatusByDecision(sub_decision, path); }}, + decision); +} + +void BlindSpotModule::reactRTCApproval( + const BlindSpotDecision & decision, PathWithLaneId * path, StopReason * stop_reason) +{ + std::visit( + VisitorSwitch{[&](const auto & sub_decision) { + reactRTCApprovalByDecision(sub_decision, path, stop_reason); + }}, + decision); +} + +bool BlindSpotModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) +{ + debug_data_ = DebugData(); + *stop_reason = planning_utils::initializeStopReason(StopReason::BLIND_SPOT); + + initializeRTCStatus(); + const auto decision = modifyPathVelocityDetail(path, stop_reason); + const auto & input_path = *path; + setRTCStatus(decision, input_path); + reactRTCApproval(decision, path, stop_reason); + return true; } @@ -259,10 +237,11 @@ std::optional BlindSpotModule::generateInterpolatedPathInf return interpolated_path_info; } -std::optional BlindSpotModule::getSiblingStraightLanelet() const +std::optional BlindSpotModule::getSiblingStraightLanelet( + const std::shared_ptr planner_data) const { - const auto lanelet_map_ptr = planner_data_->route_handler_->getLaneletMapPtr(); - const auto routing_graph_ptr = planner_data_->route_handler_->getRoutingGraphPtr(); + const auto lanelet_map_ptr = planner_data->route_handler_->getLaneletMapPtr(); + const auto routing_graph_ptr = planner_data->route_handler_->getRoutingGraphPtr(); const auto assigned_lane = lanelet_map_ptr->laneletLayer.get(lane_id_); for (const auto & prev : routing_graph_ptr->previous(assigned_lane)) { @@ -326,7 +305,7 @@ static std::optional insertPointIndex( inout_path->points, in_pose, ego_nearest_dist_threshold, ego_nearest_yaw_threshold); // vector.insert(i) inserts element on the left side of v[i] // the velocity need to be zero order hold(from prior point) - int insert_idx = closest_idx; + size_t insert_idx = closest_idx; autoware_auto_planning_msgs::msg::PathPointWithLaneId inserted_point = inout_path->points.at(closest_idx); if (planning_utils::isAheadOf(in_pose, inout_path->points.at(closest_idx).point.pose)) { @@ -349,6 +328,7 @@ std::optional> BlindSpotModule::generateStopLine( const InterpolatedPathInfo & interpolated_path_info, autoware_auto_planning_msgs::msg::PathWithLaneId * path) const { + // NOTE: this is optionally int for later subtraction const int margin_idx_dist = std::ceil(planner_param_.stop_line_margin / interpolated_path_info.ds); @@ -368,7 +348,9 @@ std::optional> BlindSpotModule::generateStopLine( if (!first_conflict_idx_ip_opt) { return std::nullopt; } - const int first_conflict_idx_ip = static_cast(first_conflict_idx_ip_opt.value()); + + // NOTE: this is optionally int for later subtraction + const auto first_conflict_idx_ip = static_cast(first_conflict_idx_ip_opt.value()); stop_idx_default_ip = static_cast(std::max(first_conflict_idx_ip - margin_idx_dist, 0)); stop_idx_critical_ip = static_cast(first_conflict_idx_ip); @@ -406,128 +388,114 @@ std::optional> BlindSpotModule::generateStopLine( return std::make_pair(stopline_idx_default_opt.value(), stopline_idx_critical_opt.value()); } -void BlindSpotModule::cutPredictPathWithDuration( - autoware_auto_perception_msgs::msg::PredictedObjects * objects_ptr, const double time_thr) const +autoware_auto_perception_msgs::msg::PredictedObject BlindSpotModule::cutPredictPathWithDuration( + const std_msgs::msg::Header & header, + const autoware_auto_perception_msgs::msg::PredictedObject & object_original, + const double time_thr) const { + auto object = object_original; const rclcpp::Time current_time = clock_->now(); - for (auto & object : objects_ptr->objects) { // each objects - for (auto & predicted_path : object.kinematics.predicted_paths) { // each predicted paths - const auto origin_path = predicted_path; - predicted_path.path.clear(); - - for (size_t k = 0; k < origin_path.path.size(); ++k) { // each path points - const auto & predicted_pose = origin_path.path.at(k); - const auto predicted_time = - rclcpp::Time(objects_ptr->header.stamp) + - rclcpp::Duration(origin_path.time_step) * static_cast(k); - if ((predicted_time - current_time).seconds() < time_thr) { - predicted_path.path.push_back(predicted_pose); - } + for (auto & predicted_path : object.kinematics.predicted_paths) { // each predicted paths + const auto origin_path = predicted_path; + predicted_path.path.clear(); + + for (size_t k = 0; k < origin_path.path.size(); ++k) { // each path points + const auto & predicted_pose = origin_path.path.at(k); + const auto predicted_time = rclcpp::Time(header.stamp) + + rclcpp::Duration(origin_path.time_step) * static_cast(k); + if ((predicted_time - current_time).seconds() < time_thr) { + predicted_path.path.push_back(predicted_pose); } } } + return object; } -bool BlindSpotModule::checkObstacleInBlindSpot( - lanelet::LaneletMapConstPtr lanelet_map_ptr, lanelet::routing::RoutingGraphPtr routing_graph_ptr, - const autoware_auto_planning_msgs::msg::PathWithLaneId & path, - const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr objects_ptr, - const int closest_idx, const geometry_msgs::msg::Pose & stop_line_pose) +std::optional BlindSpotModule::isOverPassJudge( + const autoware_auto_planning_msgs::msg::PathWithLaneId & input_path, + const geometry_msgs::msg::Pose & stop_point_pose) const { - /* get detection area */ - if (turn_direction_ == TurnDirection::INVALID) { - RCLCPP_WARN(logger_, "blind spot detector is running, turn_direction_ = not right or left."); - return false; - } - - const auto areas_opt = generateBlindSpotPolygons( - lanelet_map_ptr, routing_graph_ptr, path, closest_idx, stop_line_pose); - if (areas_opt) { - const auto & detection_areas = areas_opt.value().detection_areas; - const auto & conflict_areas = areas_opt.value().conflict_areas; - const auto & opposite_detection_areas = areas_opt.value().opposite_detection_areas; - const auto & opposite_conflict_areas = areas_opt.value().opposite_conflict_areas; - debug_data_.detection_areas = detection_areas; - debug_data_.conflict_areas = conflict_areas; - debug_data_.detection_areas.insert( - debug_data_.detection_areas.end(), opposite_detection_areas.begin(), - opposite_detection_areas.end()); - debug_data_.conflict_areas.insert( - debug_data_.conflict_areas.end(), opposite_conflict_areas.begin(), - opposite_conflict_areas.end()); - - autoware_auto_perception_msgs::msg::PredictedObjects objects = *objects_ptr; - cutPredictPathWithDuration(&objects, planner_param_.max_future_movement_time); - - // check objects in blind spot areas - for (const auto & object : objects.objects) { - if (!isTargetObjectType(object)) { - continue; - } + const auto & current_pose = planner_data_->current_odometry->pose; - // right direction - const bool exist_in_right_detection_area = - std::any_of(detection_areas.begin(), detection_areas.end(), [&object](const auto & area) { - return bg::within( - to_bg2d(object.kinematics.initial_pose_with_covariance.pose.position), - lanelet::utils::to2D(area)); - }); - // opposite direction - const bool exist_in_opposite_detection_area = std::any_of( - opposite_detection_areas.begin(), opposite_detection_areas.end(), - [&object](const auto & area) { - return bg::within( - to_bg2d(object.kinematics.initial_pose_with_covariance.pose.position), - lanelet::utils::to2D(area)); - }); - const bool exist_in_detection_area = - exist_in_right_detection_area || exist_in_opposite_detection_area; - if (!exist_in_detection_area) { - continue; - } - const bool exist_in_right_conflict_area = - isPredictedPathInArea(object, conflict_areas, planner_data_->current_odometry->pose); - const bool exist_in_opposite_conflict_area = isPredictedPathInArea( - object, opposite_conflict_areas, planner_data_->current_odometry->pose); - const bool exist_in_conflict_area = - exist_in_right_conflict_area || exist_in_opposite_conflict_area; - if (exist_in_detection_area && exist_in_conflict_area) { - debug_data_.conflicting_targets.objects.push_back(object); - setObjectsOfInterestData( - object.kinematics.initial_pose_with_covariance.pose, object.shape, ColorName::RED); - return true; - } + /* set judge line dist */ + const double pass_judge_line_dist = planning_utils::calcJudgeLineDistWithAccLimit( + planner_data_->current_velocity->twist.linear.x, planner_data_->max_stop_acceleration_threshold, + planner_data_->delay_response_time); + const auto ego_segment_idx = motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( + input_path.points, current_pose, planner_data_->ego_nearest_dist_threshold, + planner_data_->ego_nearest_yaw_threshold); + const size_t stop_point_segment_idx = + motion_utils::findNearestSegmentIndex(input_path.points, stop_point_pose.position); + const auto distance_until_stop = motion_utils::calcSignedArcLength( + input_path.points, current_pose.position, ego_segment_idx, stop_point_pose.position, + stop_point_segment_idx); + + /* if current_state = GO, and current_pose is over judge_line, ignore planning. */ + if (planner_param_.use_pass_judge_line) { + const double eps = 1e-1; // to prevent hunting + if (const auto current_state = state_machine_.getState(); + current_state == StateMachine::State::GO && + distance_until_stop + eps < pass_judge_line_dist) { + return OverPassJudge{"over the pass judge line. no plan needed."}; } - return false; - } else { - return false; } + return std::nullopt; } -bool BlindSpotModule::isPredictedPathInArea( - const autoware_auto_perception_msgs::msg::PredictedObject & object, - const std::vector & areas, geometry_msgs::msg::Pose ego_pose) const +double BlindSpotModule::computeTimeToPassStopLine( + const lanelet::ConstLanelets & blind_spot_lanelets, + const geometry_msgs::msg::Pose & stop_line_pose) const { - const auto ego_yaw = tf2::getYaw(ego_pose.orientation); - const auto threshold_yaw_diff = planner_param_.threshold_yaw_diff; - // NOTE: iterating all paths including those of low confidence - return std::any_of( - areas.begin(), areas.end(), [&object, &ego_yaw, &threshold_yaw_diff](const auto & area) { - const auto area_2d = lanelet::utils::to2D(area); - return std::any_of( - object.kinematics.predicted_paths.begin(), object.kinematics.predicted_paths.end(), - [&area_2d, &ego_yaw, &threshold_yaw_diff](const auto & path) { - return std::any_of( - path.path.begin(), path.path.end(), - [&area_2d, &ego_yaw, &threshold_yaw_diff](const auto & point) { - const auto is_in_area = bg::within(to_bg2d(point.position), area_2d); - const auto match_yaw = - std::fabs(ego_yaw - tf2::getYaw(point.orientation)) < threshold_yaw_diff; - return is_in_area && match_yaw; - }); - }); - }); + // egoが停止している時にそのまま速度を使うと衝突しなくなってしまうのでegoについては最低速度を使う + const auto & current_pose = planner_data_->current_odometry->pose; + const auto current_arc_ego = + lanelet::utils::getArcCoordinates(blind_spot_lanelets, current_pose).length; + const auto stopline_arc_ego = + lanelet::utils::getArcCoordinates(blind_spot_lanelets, stop_line_pose).length; + const auto remaining_distance = stopline_arc_ego - current_arc_ego; + return remaining_distance / std::max( + planner_param_.ttc_ego_minimal_velocity, + planner_data_->current_velocity->twist.linear.x); +} + +std::optional +BlindSpotModule::isCollisionDetected( + const lanelet::ConstLanelets & blind_spot_lanelets, + const geometry_msgs::msg::Pose & stop_line_pose, const lanelet::CompoundPolygon3d & area, + const double ego_time_to_reach_stop_line) +{ + // check objects in blind spot areas + const auto stop_line_arc_ego = + lanelet::utils::getArcCoordinates(blind_spot_lanelets, stop_line_pose).length; + for (const auto & original_object : planner_data_->predicted_objects->objects) { + if (!isTargetObjectType(original_object)) { + continue; + } + const auto object = cutPredictPathWithDuration( + planner_data_->predicted_objects->header, original_object, + planner_param_.max_future_movement_time); + // right direction + const bool exist_in_detection_area = bg::within( + to_bg2d(object.kinematics.initial_pose_with_covariance.pose.position), + lanelet::utils::to2D(area)); + if (!exist_in_detection_area) { + continue; + } + const auto object_arc_length = + lanelet::utils::getArcCoordinates( + blind_spot_lanelets, object.kinematics.initial_pose_with_covariance.pose) + .length; + const auto object_time_to_reach_stop_line = + (object_arc_length - stop_line_arc_ego) / + (object.kinematics.initial_twist_with_covariance.twist.linear.x); + const auto ttc = ego_time_to_reach_stop_line - object_time_to_reach_stop_line; + RCLCPP_INFO(logger_, "object ttc is %f", ttc); + if (planner_param_.ttc_min < ttc && ttc < planner_param_.ttc_max) { + return object; + } + } + return std::nullopt; } lanelet::ConstLanelet BlindSpotModule::generateHalfLanelet( @@ -554,8 +522,6 @@ lanelet::ConstLanelet BlindSpotModule::generateHalfLanelet( const auto left_bound = lanelet::LineString3d(lanelet::InvalId, std::move(lefts)); const auto right_bound = lanelet::LineString3d(lanelet::InvalId, std::move(rights)); auto half_lanelet = lanelet::Lanelet(lanelet::InvalId, left_bound, right_bound); - const auto centerline = lanelet::utils::generateFineCenterline(half_lanelet, 5.0); - half_lanelet.setCenterline(centerline); return half_lanelet; } @@ -620,15 +586,23 @@ lanelet::ConstLanelet BlindSpotModule::generateExtendedOppositeAdjacentLanelet( return new_lanelet; } -std::optional BlindSpotModule::generateBlindSpotPolygons( - lanelet::LaneletMapConstPtr lanelet_map_ptr, - [[maybe_unused]] lanelet::routing::RoutingGraphPtr routing_graph_ptr, - const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const int closest_idx, - const geometry_msgs::msg::Pose & stop_line_pose) const +static lanelet::LineString3d removeConst(lanelet::ConstLineString3d line) { + lanelet::Points3d pts; + for (const auto & pt : line) { + pts.push_back(lanelet::Point3d(pt)); + } + return lanelet::LineString3d(lanelet::InvalId, pts); +} + +lanelet::ConstLanelets BlindSpotModule::generateBlindSpotLanelets( + const autoware_auto_planning_msgs::msg::PathWithLaneId & path) const +{ + /* get lanelet map */ + const auto lanelet_map_ptr = planner_data_->route_handler_->getLaneletMapPtr(); + const auto routing_graph_ptr = planner_data_->route_handler_->getRoutingGraphPtr(); + std::vector lane_ids; - lanelet::ConstLanelets blind_spot_lanelets; - lanelet::ConstLanelets blind_spot_opposite_lanelets; /* get lane ids until intersection */ for (const auto & point : path.points) { bool found_intersection_lane = false; @@ -646,17 +620,10 @@ std::optional BlindSpotModule::generateBlindSpotPolygons( if (found_intersection_lane) break; } - for (size_t i = 0; i < lane_ids.size(); ++i) { - const auto half_lanelet = - generateHalfLanelet(lanelet_map_ptr->laneletLayer.get(lane_ids.at(i))); - blind_spot_lanelets.push_back(half_lanelet); - } - - // additional detection area on left/right side - lanelet::ConstLanelets adjacent_lanelets; - lanelet::ConstLanelets opposite_adjacent_lanelets; + lanelet::ConstLanelets blind_spot_lanelets; for (const auto i : lane_ids) { const auto lane = lanelet_map_ptr->laneletLayer.get(i); + const auto ego_half_lanelet = generateHalfLanelet(lane); const auto adj = turn_direction_ == TurnDirection::LEFT ? (routing_graph_ptr->adjacentLeft(lane)) @@ -688,66 +655,42 @@ std::optional BlindSpotModule::generateBlindSpotPolygons( return std::nullopt; } }(); - if (adj) { - const auto half_lanelet = generateExtendedAdjacentLanelet(adj.value(), turn_direction_); - adjacent_lanelets.push_back(half_lanelet); - } - if (opposite_adj) { - const auto half_lanelet = + + if (!adj && !opposite_adj) { + blind_spot_lanelets.push_back(ego_half_lanelet); + } else if (!!adj) { + const auto adj_half_lanelet = generateExtendedAdjacentLanelet(adj.value(), turn_direction_); + const auto lefts = (turn_direction_ == TurnDirection::LEFT) ? adj_half_lanelet.leftBound() + : ego_half_lanelet.leftBound(); + const auto rights = (turn_direction_ == TurnDirection::RIGHT) ? adj_half_lanelet.rightBound() + : ego_half_lanelet.rightBound(); + blind_spot_lanelets.push_back( + lanelet::ConstLanelet(lanelet::InvalId, removeConst(lefts), removeConst(rights))); + } else if (opposite_adj) { + const auto adj_half_lanelet = generateExtendedOppositeAdjacentLanelet(opposite_adj.value(), turn_direction_); - opposite_adjacent_lanelets.push_back(half_lanelet); + const auto lefts = (turn_direction_ == TurnDirection::LEFT) ? adj_half_lanelet.leftBound() + : ego_half_lanelet.leftBound(); + const auto rights = (turn_direction_ == TurnDirection::LEFT) ? ego_half_lanelet.rightBound() + : adj_half_lanelet.rightBound(); + blind_spot_lanelets.push_back( + lanelet::ConstLanelet(lanelet::InvalId, removeConst(lefts), removeConst(rights))); } } + return blind_spot_lanelets; +} - const auto current_arc_ego = - lanelet::utils::getArcCoordinates(blind_spot_lanelets, path.points[closest_idx].point.pose) - .length; +std::optional BlindSpotModule::generateBlindSpotPolygons( + [[maybe_unused]] const autoware_auto_planning_msgs::msg::PathWithLaneId & path, + [[maybe_unused]] const size_t closest_idx, const lanelet::ConstLanelets & blind_spot_lanelets, + const geometry_msgs::msg::Pose & stop_line_pose) const +{ const auto stop_line_arc_ego = lanelet::utils::getArcCoordinates(blind_spot_lanelets, stop_line_pose).length; - const auto detection_area_start_length_ego = stop_line_arc_ego - planner_param_.backward_length; - if (detection_area_start_length_ego < current_arc_ego && current_arc_ego < stop_line_arc_ego) { - BlindSpotPolygons blind_spot_polygons; - auto conflict_area_ego = lanelet::utils::getPolygonFromArcLength( - blind_spot_lanelets, current_arc_ego, stop_line_arc_ego); - auto detection_area_ego = lanelet::utils::getPolygonFromArcLength( - blind_spot_lanelets, detection_area_start_length_ego, stop_line_arc_ego); - blind_spot_polygons.conflict_areas.emplace_back(std::move(conflict_area_ego)); - blind_spot_polygons.detection_areas.emplace_back(std::move(detection_area_ego)); - // additional detection area on left/right side - if (!adjacent_lanelets.empty()) { - const auto stop_line_arc_adj = lanelet::utils::getLaneletLength3d(adjacent_lanelets); - const auto current_arc_adj = stop_line_arc_adj - (stop_line_arc_ego - current_arc_ego); - const auto detection_area_start_length_adj = - stop_line_arc_adj - planner_param_.backward_length; - auto conflicting_area_adj = lanelet::utils::getPolygonFromArcLength( - adjacent_lanelets, current_arc_adj, stop_line_arc_adj); - auto detection_area_adj = lanelet::utils::getPolygonFromArcLength( - adjacent_lanelets, detection_area_start_length_adj, stop_line_arc_adj); - blind_spot_polygons.conflict_areas.emplace_back(std::move(conflicting_area_adj)); - blind_spot_polygons.detection_areas.emplace_back(std::move(detection_area_adj)); - } - // additional detection area on left/right opposite lane side - if (!opposite_adjacent_lanelets.empty()) { - const auto stop_line_arc_opposite_adj = - lanelet::utils::getLaneletLength3d(opposite_adjacent_lanelets); - const auto current_arc_opposite_adj = - stop_line_arc_opposite_adj - (stop_line_arc_ego - current_arc_ego); - const auto detection_area_start_length_opposite_adj = - stop_line_arc_opposite_adj - planner_param_.backward_length; - auto conflicting_area_opposite_adj = lanelet::utils::getPolygonFromArcLength( - opposite_adjacent_lanelets, current_arc_opposite_adj, stop_line_arc_opposite_adj); - auto detection_area_opposite_adj = lanelet::utils::getPolygonFromArcLength( - opposite_adjacent_lanelets, detection_area_start_length_opposite_adj, - stop_line_arc_opposite_adj); - blind_spot_polygons.opposite_conflict_areas.emplace_back( - std::move(conflicting_area_opposite_adj)); - blind_spot_polygons.opposite_detection_areas.emplace_back( - std::move(detection_area_opposite_adj)); - } - return blind_spot_polygons; - } else { - return std::nullopt; - } + const auto detection_area_start_length_ego = + std::max(stop_line_arc_ego - planner_param_.backward_detection_length, 0.0); + return lanelet::utils::getPolygonFromArcLength( + blind_spot_lanelets, detection_area_start_length_ego, stop_line_arc_ego); } bool BlindSpotModule::isTargetObjectType( diff --git a/planning/behavior_velocity_blind_spot_module/src/scene.hpp b/planning/behavior_velocity_blind_spot_module/src/scene.hpp index fd93661b33d6b..709942794ec1e 100644 --- a/planning/behavior_velocity_blind_spot_module/src/scene.hpp +++ b/planning/behavior_velocity_blind_spot_module/src/scene.hpp @@ -31,18 +31,11 @@ #include #include #include +#include #include namespace behavior_velocity_planner { -struct BlindSpotPolygons -{ - std::vector conflict_areas; - std::vector detection_areas; - std::vector opposite_conflict_areas; - std::vector opposite_detection_areas; -}; - /** * @brief wrapper class of interpolated path with lane id */ @@ -58,42 +51,63 @@ struct InterpolatedPathInfo std::optional> lane_id_interval{std::nullopt}; }; +/** + * @brief represent action + */ +struct InternalError +{ + const std::string error; +}; + +struct OverPassJudge +{ + const std::string report; +}; + +struct Unsafe +{ + const size_t stop_line_idx; + const std::optional collision_obstacle; +}; + +struct Safe +{ + const size_t stop_line_idx; +}; + +using BlindSpotDecision = std::variant; + class BlindSpotModule : public SceneModuleInterface { public: - enum class TurnDirection { LEFT = 0, RIGHT, INVALID }; + enum class TurnDirection { LEFT, RIGHT }; struct DebugData { - geometry_msgs::msg::Pose virtual_wall_pose; - geometry_msgs::msg::Pose stop_point_pose; - geometry_msgs::msg::Pose judge_point_pose; - std::vector conflict_areas; - std::vector detection_areas; - std::vector opposite_conflict_areas; - std::vector opposite_detection_areas; + std::optional virtual_wall_pose{std::nullopt}; + std::optional detection_area; autoware_auto_perception_msgs::msg::PredictedObjects conflicting_targets; }; public: struct PlannerParam { - bool use_pass_judge_line; //! distance which ego can stop with max brake - double stop_line_margin; //! distance from auto-generated stopline to detection_area boundary - double backward_length; //! distance[m] from closest path point to the edge of beginning point - double ignore_width_from_center_line; //! ignore width from center line from detection_area - double - max_future_movement_time; //! maximum time[second] for considering future movement of object - double threshold_yaw_diff; //! threshold of yaw difference between ego and target object - double - adjacent_extend_width; //! the width of extended detection/conflict area on adjacent lane + bool use_pass_judge_line; + double stop_line_margin; + double backward_detection_length; + double ignore_width_from_center_line; + double adjacent_extend_width; double opposite_adjacent_extend_width; + double max_future_movement_time; + double ttc_min; + double ttc_max; + double ttc_ego_minimal_velocity; }; BlindSpotModule( - const int64_t module_id, const int64_t lane_id, std::shared_ptr planner_data, - const PlannerParam & planner_param, const rclcpp::Logger logger, - const rclcpp::Clock::SharedPtr clock); + const int64_t module_id, const int64_t lane_id, const TurnDirection turn_direction, + const std::shared_ptr planner_data, const PlannerParam & planner_param, + const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock); /** * @brief plan go-stop velocity at traffic crossing with collision check between reference path @@ -105,18 +119,40 @@ class BlindSpotModule : public SceneModuleInterface std::vector createVirtualWalls() override; private: + // (semi) const variables const int64_t lane_id_; const PlannerParam planner_param_; - TurnDirection turn_direction_{TurnDirection::INVALID}; - bool is_over_pass_judge_line_{false}; + const TurnDirection turn_direction_; std::optional sibling_straight_lanelet_{std::nullopt}; + std::optional blind_spot_lanelets_{std::nullopt}; + + // state variables + bool is_over_pass_judge_line_{false}; // Parameter + void initializeRTCStatus(); + BlindSpotDecision modifyPathVelocityDetail(PathWithLaneId * path, StopReason * stop_reason); + // setSafe(), setDistance() + void setRTCStatus( + const BlindSpotDecision & decision, + const autoware_auto_planning_msgs::msg::PathWithLaneId & path); + template + void setRTCStatusByDecision( + const Decision & decision, const autoware_auto_planning_msgs::msg::PathWithLaneId & path); + // stop/GO + void reactRTCApproval( + const BlindSpotDecision & decision, PathWithLaneId * path, StopReason * stop_reason); + template + void reactRTCApprovalByDecision( + const Decision & decision, autoware_auto_planning_msgs::msg::PathWithLaneId * path, + StopReason * stop_reason); + std::optional generateInterpolatedPathInfo( const autoware_auto_planning_msgs::msg::PathWithLaneId & input_path) const; - std::optional getSiblingStraightLanelet() const; + std::optional getSiblingStraightLanelet( + const std::shared_ptr planner_data) const; /** * @brief Generate a stop line and insert it into the path. @@ -131,6 +167,14 @@ class BlindSpotModule : public SceneModuleInterface const InterpolatedPathInfo & interpolated_path_info, autoware_auto_planning_msgs::msg::PathWithLaneId * path) const; + std::optional isOverPassJudge( + const autoware_auto_planning_msgs::msg::PathWithLaneId & path, + const geometry_msgs::msg::Pose & stop_point_pose) const; + + double computeTimeToPassStopLine( + const lanelet::ConstLanelets & blind_spot_lanelets, + const geometry_msgs::msg::Pose & stop_line_pose) const; + /** * @brief Check obstacle is in blind spot areas. * Condition1: Object's position is in broad blind spot area. @@ -141,12 +185,10 @@ class BlindSpotModule : public SceneModuleInterface * @param closest_idx closest path point index from ego car in path points * @return true when an object is detected in blind spot */ - bool checkObstacleInBlindSpot( - lanelet::LaneletMapConstPtr lanelet_map_ptr, - lanelet::routing::RoutingGraphPtr routing_graph_ptr, - const autoware_auto_planning_msgs::msg::PathWithLaneId & path, - const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr objects_ptr, - const int closest_idx, const geometry_msgs::msg::Pose & stop_line_pose); + std::optional isCollisionDetected( + const lanelet::ConstLanelets & blind_spot_lanelets, + const geometry_msgs::msg::Pose & stop_line_pose, const lanelet::CompoundPolygon3d & area, + const double ego_time_to_reach_stop_line); /** * @brief Create half lanelet @@ -160,6 +202,9 @@ class BlindSpotModule : public SceneModuleInterface lanelet::ConstLanelet generateExtendedOppositeAdjacentLanelet( const lanelet::ConstLanelet lanelet, const TurnDirection direction) const; + lanelet::ConstLanelets generateBlindSpotLanelets( + const autoware_auto_planning_msgs::msg::PathWithLaneId & path) const; + /** * @brief Make blind spot areas. Narrow area is made from closest path point to stop line index. * Broad area is made from backward expanded point to stop line point @@ -167,10 +212,9 @@ class BlindSpotModule : public SceneModuleInterface * @param closest_idx closest path point index from ego car in path points * @return Blind spot polygons */ - std::optional generateBlindSpotPolygons( - lanelet::LaneletMapConstPtr lanelet_map_ptr, - lanelet::routing::RoutingGraphPtr routing_graph_ptr, - const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const int closest_idx, + std::optional generateBlindSpotPolygons( + const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const size_t closest_idx, + const lanelet::ConstLanelets & blind_spot_lanelets, const geometry_msgs::msg::Pose & pose) const; /** @@ -180,23 +224,14 @@ class BlindSpotModule : public SceneModuleInterface */ bool isTargetObjectType(const autoware_auto_perception_msgs::msg::PredictedObject & object) const; - /** - * @brief Check if at least one of object's predicted position is in area - * @param object Dynamic object - * @param area Area defined by polygon - * @return True when at least one of object's predicted position is in area - */ - bool isPredictedPathInArea( - const autoware_auto_perception_msgs::msg::PredictedObject & object, - const std::vector & areas, geometry_msgs::msg::Pose ego_pose) const; - /** * @brief Modify objects predicted path. remove path point if the time exceeds timer_thr. * @param objects_ptr target objects * @param time_thr time threshold to cut path */ - void cutPredictPathWithDuration( - autoware_auto_perception_msgs::msg::PredictedObjects * objects_ptr, + autoware_auto_perception_msgs::msg::PredictedObject cutPredictPathWithDuration( + const std_msgs::msg::Header & header, + const autoware_auto_perception_msgs::msg::PredictedObject & object, const double time_thr) const; StateMachine state_machine_; //! for state diff --git a/planning/behavior_velocity_crosswalk_module/CMakeLists.txt b/planning/behavior_velocity_crosswalk_module/CMakeLists.txt index 69dd1ced695ec..f21d5ab786cad 100644 --- a/planning/behavior_velocity_crosswalk_module/CMakeLists.txt +++ b/planning/behavior_velocity_crosswalk_module/CMakeLists.txt @@ -3,7 +3,7 @@ project(behavior_velocity_crosswalk_module) find_package(autoware_cmake REQUIRED) autoware_package() -pluginlib_export_plugin_description_file(behavior_velocity_planner plugins.xml) +pluginlib_export_plugin_description_file(autoware_behavior_velocity_planner plugins.xml) ament_auto_add_library(${PROJECT_NAME} SHARED DIRECTORY diff --git a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml index f8b9e5dbf1327..67b923a8d4cd8 100644 --- a/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml +++ b/planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml @@ -43,6 +43,7 @@ ego_pass_later_margin_x: [0.0] # [[s]] time to vehicle margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition) ego_pass_later_margin_y: [13.0] # [[s]] time to collision margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition) ego_pass_later_additional_margin: 0.5 # [s] additional time margin for object pass first situation to suppress chattering + ego_min_assumed_speed: 2.0 # [m/s] assumed speed to calculate the time to collision point no_stop_decision: # parameters to determine if it is safe to attempt stopping before the crosswalk max_offset_to_crosswalk_for_yield: 0.0 # [m] maximum offset from ego's front to crosswalk for yield. Positive value means in front of the crosswalk. diff --git a/planning/behavior_velocity_crosswalk_module/src/manager.cpp b/planning/behavior_velocity_crosswalk_module/src/manager.cpp index aeff5e27cea7b..5110ff9993a62 100644 --- a/planning/behavior_velocity_crosswalk_module/src/manager.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/manager.cpp @@ -90,6 +90,8 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node) getOrDeclareParameter>(node, ns + ".pass_judge.ego_pass_later_margin_y"); cp.ego_pass_later_additional_margin = getOrDeclareParameter(node, ns + ".pass_judge.ego_pass_later_additional_margin"); + cp.ego_min_assumed_speed = + getOrDeclareParameter(node, ns + ".pass_judge.ego_min_assumed_speed"); cp.max_offset_to_crosswalk_for_yield = getOrDeclareParameter( node, ns + ".pass_judge.no_stop_decision.max_offset_to_crosswalk_for_yield"); cp.min_acc_for_no_stop_decision = @@ -188,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_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 86038c721604d..0f9c753523f13 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -810,8 +810,6 @@ CollisionPoint CrosswalkModule::createCollisionPoint( const geometry_msgs::msg::Vector3 & obj_vel, const std::optional object_crosswalk_passage_direction) const { - constexpr double min_ego_velocity = 1.38; // [m/s] - const auto estimated_velocity = std::hypot(obj_vel.x, obj_vel.y); const auto velocity = std::max(planner_param_.min_object_velocity, estimated_velocity); @@ -824,7 +822,7 @@ CollisionPoint CrosswalkModule::createCollisionPoint( // Hence, here, we use the length that would be appropriate for the ego_pass_first judge. collision_point.time_to_collision = std::max(0.0, dist_ego2cp - planner_data_->vehicle_info_.min_longitudinal_offset_m) / - std::max(ego_vel.x, min_ego_velocity); + std::max(ego_vel.x, planner_param_.ego_min_assumed_speed); collision_point.time_to_vehicle = std::max(0.0, dist_obj2cp) / velocity; return 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 bc89936fe883a..faba8730aa6d9 100644 --- a/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -135,6 +135,7 @@ class CrosswalkModule : public SceneModuleInterface std::vector ego_pass_later_margin_x; std::vector ego_pass_later_margin_y; double ego_pass_later_additional_margin; + double ego_min_assumed_speed; double max_offset_to_crosswalk_for_yield; double min_acc_for_no_stop_decision; double max_jerk_for_no_stop_decision; @@ -181,7 +182,7 @@ class CrosswalkModule : public SceneModuleInterface 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 bool is_object_on_ego_path) + const bool is_object_away_from_path) { const bool is_stopped = vel < planner_param.stop_object_velocity; @@ -201,7 +202,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 && !is_object_on_ego_path) { + if (is_ego_yielding && !intent_to_cross && is_object_away_from_path) { collision_state = CollisionState::IGNORE; return; } @@ -260,15 +261,16 @@ class CrosswalkModule : public SceneModuleInterface // 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; + const bool is_object_away_from_path = + !attention_area.outer().empty() && + 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 && - !is_object_on_ego_path) { + is_object_away_from_path) { objects.emplace(uuid, ObjectInfo{CollisionState::IGNORE}); } else { objects.emplace(uuid, ObjectInfo{CollisionState::YIELD}); @@ -278,7 +280,7 @@ class CrosswalkModule : public SceneModuleInterface // update object state objects.at(uuid).transitState( now, position, vel, is_ego_yielding, collision_point, planner_param, crosswalk_polygon, - is_object_on_ego_path); + is_object_away_from_path); objects.at(uuid).collision_point = collision_point; objects.at(uuid).position = position; objects.at(uuid).classification = classification; diff --git a/planning/behavior_velocity_detection_area_module/CMakeLists.txt b/planning/behavior_velocity_detection_area_module/CMakeLists.txt index 2a16ed95ba655..e6990d2d28642 100644 --- a/planning/behavior_velocity_detection_area_module/CMakeLists.txt +++ b/planning/behavior_velocity_detection_area_module/CMakeLists.txt @@ -3,7 +3,7 @@ project(behavior_velocity_detection_area_module) find_package(autoware_cmake REQUIRED) autoware_package() -pluginlib_export_plugin_description_file(behavior_velocity_planner plugins.xml) +pluginlib_export_plugin_description_file(autoware_behavior_velocity_planner plugins.xml) ament_auto_add_library(${PROJECT_NAME} SHARED src/debug.cpp 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_dynamic_obstacle_stop_module/CMakeLists.txt b/planning/behavior_velocity_dynamic_obstacle_stop_module/CMakeLists.txt index 20f4b3aa8f4d3..481ac245cb432 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/CMakeLists.txt +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/CMakeLists.txt @@ -3,7 +3,7 @@ project(behavior_velocity_dynamic_obstacle_stop_module) find_package(autoware_cmake REQUIRED) autoware_package() -pluginlib_export_plugin_description_file(behavior_velocity_planner plugins.xml) +pluginlib_export_plugin_description_file(autoware_behavior_velocity_planner plugins.xml) ament_auto_add_library(${PROJECT_NAME} SHARED DIRECTORY src diff --git a/planning/behavior_velocity_intersection_module/CMakeLists.txt b/planning/behavior_velocity_intersection_module/CMakeLists.txt index 07847a08c1209..c02b5a3852722 100644 --- a/planning/behavior_velocity_intersection_module/CMakeLists.txt +++ b/planning/behavior_velocity_intersection_module/CMakeLists.txt @@ -3,7 +3,7 @@ project(behavior_velocity_intersection_module) find_package(autoware_cmake REQUIRED) autoware_package() -pluginlib_export_plugin_description_file(behavior_velocity_planner plugins.xml) +pluginlib_export_plugin_description_file(autoware_behavior_velocity_planner plugins.xml) find_package(OpenCV REQUIRED) 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_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_no_drivable_lane_module/CMakeLists.txt b/planning/behavior_velocity_no_drivable_lane_module/CMakeLists.txt index ef3073df56c22..265b5b637e7ce 100644 --- a/planning/behavior_velocity_no_drivable_lane_module/CMakeLists.txt +++ b/planning/behavior_velocity_no_drivable_lane_module/CMakeLists.txt @@ -3,7 +3,7 @@ project(behavior_velocity_no_drivable_lane_module) find_package(autoware_cmake REQUIRED) autoware_package() -pluginlib_export_plugin_description_file(behavior_velocity_planner plugins.xml) +pluginlib_export_plugin_description_file(autoware_behavior_velocity_planner plugins.xml) ament_auto_add_library(${PROJECT_NAME} SHARED src/debug.cpp diff --git a/planning/behavior_velocity_no_stopping_area_module/CMakeLists.txt b/planning/behavior_velocity_no_stopping_area_module/CMakeLists.txt index 4d14228c4685c..ba3fd0e4f71dd 100644 --- a/planning/behavior_velocity_no_stopping_area_module/CMakeLists.txt +++ b/planning/behavior_velocity_no_stopping_area_module/CMakeLists.txt @@ -3,7 +3,7 @@ project(behavior_velocity_no_stopping_area_module) find_package(autoware_cmake REQUIRED) autoware_package() -pluginlib_export_plugin_description_file(behavior_velocity_planner plugins.xml) +pluginlib_export_plugin_description_file(autoware_behavior_velocity_planner plugins.xml) ament_auto_add_library(${PROJECT_NAME} SHARED src/debug.cpp 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_no_stopping_area_module/src/scene_no_stopping_area.cpp b/planning/behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp index 92afd25026a70..7b886fea09b34 100644 --- a/planning/behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp +++ b/planning/behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp @@ -87,12 +87,8 @@ boost::optional NoStoppingAreaModule::getStopLineGeometry2d( const LineString2d line{{p0.x, p0.y}, {p1.x, p1.y}}; std::vector collision_points; bg::intersection(area_poly, line, collision_points); - if (collision_points.empty()) { - continue; - } - const double yaw = tier4_autoware_utils::calcAzimuthAngle(p0, p1); if (!collision_points.empty()) { - geometry_msgs::msg::Point left_point; + const double yaw = tier4_autoware_utils::calcAzimuthAngle(p0, p1); const double w = planner_data_->vehicle_info_.vehicle_width_m; const double l = stop_line_margin; stop_line.emplace_back( @@ -306,7 +302,6 @@ Polygon2d NoStoppingAreaModule::generateEgoNoStoppingAreaLanePolygon( const int num_ignore_nearest = 1; // Do not consider nearest lane polygon size_t ego_area_start_idx = closest_idx + num_ignore_nearest; - size_t ego_area_end_idx = ego_area_start_idx; // return if area size is not intentional if (no_stopping_area_reg_elem_.noStoppingAreas().size() != 1) { return ego_area; @@ -330,7 +325,7 @@ Polygon2d NoStoppingAreaModule::generateEgoNoStoppingAreaLanePolygon( } double dist_from_area_sum = 0.0; // decide end idx with extract distance - ego_area_end_idx = ego_area_start_idx; + size_t ego_area_end_idx = ego_area_start_idx; for (size_t i = ego_area_start_idx; i < pp.size() - 1; ++i) { dist_from_start_sum += tier4_autoware_utils::calcDistance2d(pp.at(i), pp.at(i - 1)); const auto & p = pp.at(i).point.pose.position; diff --git a/planning/behavior_velocity_occlusion_spot_module/CMakeLists.txt b/planning/behavior_velocity_occlusion_spot_module/CMakeLists.txt index 7a062ee854421..8b327291a60f1 100644 --- a/planning/behavior_velocity_occlusion_spot_module/CMakeLists.txt +++ b/planning/behavior_velocity_occlusion_spot_module/CMakeLists.txt @@ -3,7 +3,7 @@ project(behavior_velocity_occlusion_spot_module) find_package(autoware_cmake REQUIRED) autoware_package() -pluginlib_export_plugin_description_file(behavior_velocity_planner plugins.xml) +pluginlib_export_plugin_description_file(autoware_behavior_velocity_planner plugins.xml) ament_auto_add_library(${PROJECT_NAME} SHARED src/debug.cpp diff --git a/planning/behavior_velocity_occlusion_spot_module/src/debug.cpp b/planning/behavior_velocity_occlusion_spot_module/src/debug.cpp index a6e13d0dfdcdc..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; @@ -118,7 +117,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..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 @@ -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; @@ -242,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; @@ -257,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); } @@ -286,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. * ^ @@ -338,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, @@ -426,7 +433,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; @@ -451,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 ec58e38dec45a..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; @@ -241,7 +237,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, diff --git a/planning/behavior_velocity_out_of_lane_module/CMakeLists.txt b/planning/behavior_velocity_out_of_lane_module/CMakeLists.txt index 8ce1a334c4b35..e8191f9b632d5 100644 --- a/planning/behavior_velocity_out_of_lane_module/CMakeLists.txt +++ b/planning/behavior_velocity_out_of_lane_module/CMakeLists.txt @@ -3,7 +3,7 @@ project(behavior_velocity_out_of_lane_module) find_package(autoware_cmake REQUIRED) autoware_package() -pluginlib_export_plugin_description_file(behavior_velocity_planner plugins.xml) +pluginlib_export_plugin_description_file(autoware_behavior_velocity_planner plugins.xml) ament_auto_add_library(${PROJECT_NAME} SHARED DIRECTORY src 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 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 d8b042ec880e4..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 @@ -16,8 +16,8 @@ #define BEHAVIOR_VELOCITY_PLANNER_COMMON__SCENE_MODULE_INTERFACE_HPP_ #include -#include #include +#include #include #include #include @@ -31,6 +31,7 @@ #include #include #include +#include #include #include @@ -49,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; @@ -58,6 +61,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 @@ -126,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) @@ -235,14 +239,19 @@ 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); } - 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 362493005eb17..eb43e45d55711 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); } @@ -271,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/behavior_velocity_planner_common/src/velocity_factor_interface.cpp b/planning/behavior_velocity_planner_common/src/velocity_factor_interface.cpp deleted file mode 100644 index 7bc46846afb83..0000000000000 --- a/planning/behavior_velocity_planner_common/src/velocity_factor_interface.cpp +++ /dev/null @@ -1,34 +0,0 @@ -// 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. - -#include -#include - -namespace behavior_velocity_planner -{ -void VelocityFactorInterface::set( - const std::vector & points, - const Pose & curr_pose, const Pose & stop_pose, const VelocityFactorStatus status, - 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_.status = status; - velocity_factor_.detail = detail; -} - -} // namespace behavior_velocity_planner diff --git a/planning/behavior_velocity_run_out_module/CMakeLists.txt b/planning/behavior_velocity_run_out_module/CMakeLists.txt index 21758c4d0198c..3ee589ba69740 100644 --- a/planning/behavior_velocity_run_out_module/CMakeLists.txt +++ b/planning/behavior_velocity_run_out_module/CMakeLists.txt @@ -3,7 +3,7 @@ project(behavior_velocity_run_out_module) find_package(autoware_cmake REQUIRED) autoware_package() -pluginlib_export_plugin_description_file(behavior_velocity_planner plugins.xml) +pluginlib_export_plugin_description_file(autoware_behavior_velocity_planner plugins.xml) ament_auto_add_library(${PROJECT_NAME} SHARED src/debug.cpp 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 diff --git a/planning/behavior_velocity_speed_bump_module/CMakeLists.txt b/planning/behavior_velocity_speed_bump_module/CMakeLists.txt index a96eb3398e5c0..f5d3a7078be9c 100644 --- a/planning/behavior_velocity_speed_bump_module/CMakeLists.txt +++ b/planning/behavior_velocity_speed_bump_module/CMakeLists.txt @@ -3,7 +3,7 @@ project(behavior_velocity_speed_bump_module) find_package(autoware_cmake REQUIRED) autoware_package() -pluginlib_export_plugin_description_file(behavior_velocity_planner plugins.xml) +pluginlib_export_plugin_description_file(autoware_behavior_velocity_planner plugins.xml) ament_auto_add_library(${PROJECT_NAME} SHARED src/debug.cpp diff --git a/planning/behavior_velocity_stop_line_module/CMakeLists.txt b/planning/behavior_velocity_stop_line_module/CMakeLists.txt index 3c8cc6a4f9626..bef98aafe6f75 100644 --- a/planning/behavior_velocity_stop_line_module/CMakeLists.txt +++ b/planning/behavior_velocity_stop_line_module/CMakeLists.txt @@ -3,7 +3,7 @@ project(behavior_velocity_stop_line_module) find_package(autoware_cmake REQUIRED) autoware_package() -pluginlib_export_plugin_description_file(behavior_velocity_planner plugins.xml) +pluginlib_export_plugin_description_file(autoware_behavior_velocity_planner plugins.xml) ament_auto_add_library(${PROJECT_NAME} SHARED src/debug.cpp diff --git a/planning/behavior_velocity_template_module/CMakeLists.txt b/planning/behavior_velocity_template_module/CMakeLists.txt index e0beb42daf50d..103a3d0a4ceb3 100644 --- a/planning/behavior_velocity_template_module/CMakeLists.txt +++ b/planning/behavior_velocity_template_module/CMakeLists.txt @@ -3,7 +3,7 @@ project(behavior_velocity_template_module) find_package(autoware_cmake REQUIRED) autoware_package() -pluginlib_export_plugin_description_file(behavior_velocity_planner plugins.xml) +pluginlib_export_plugin_description_file(autoware_behavior_velocity_planner plugins.xml) ament_auto_add_library(${PROJECT_NAME} SHARED src/manager.cpp diff --git a/planning/behavior_velocity_traffic_light_module/CMakeLists.txt b/planning/behavior_velocity_traffic_light_module/CMakeLists.txt index cf9392fa0568f..5737802408996 100644 --- a/planning/behavior_velocity_traffic_light_module/CMakeLists.txt +++ b/planning/behavior_velocity_traffic_light_module/CMakeLists.txt @@ -3,7 +3,7 @@ project(behavior_velocity_traffic_light_module) find_package(autoware_cmake REQUIRED) autoware_package() -pluginlib_export_plugin_description_file(behavior_velocity_planner plugins.xml) +pluginlib_export_plugin_description_file(autoware_behavior_velocity_planner plugins.xml) ament_auto_add_library(${PROJECT_NAME} SHARED src/debug.cpp diff --git a/planning/behavior_velocity_traffic_light_module/package.xml b/planning/behavior_velocity_traffic_light_module/package.xml index 33bb471e5920c..544e14f130a7e 100644 --- a/planning/behavior_velocity_traffic_light_module/package.xml +++ b/planning/behavior_velocity_traffic_light_module/package.xml @@ -8,6 +8,7 @@ Satoshi Ota Tomoya Kimura Shumpei Wakabayashi + Mamoru Sobue Apache License 2.0 diff --git a/planning/behavior_velocity_traffic_light_module/src/manager.cpp b/planning/behavior_velocity_traffic_light_module/src/manager.cpp index 89817f3342dbd..edddef5cef4d8 100644 --- a/planning/behavior_velocity_traffic_light_module/src/manager.cpp +++ b/planning/behavior_velocity_traffic_light_module/src/manager.cpp @@ -62,7 +62,7 @@ void TrafficLightModuleManager::modifyPathVelocity( stop_reason_array.header.stamp = path->header.stamp; first_stop_path_point_index_ = static_cast(path->points.size() - 1); - first_ref_stop_path_point_index_ = static_cast(path->points.size() - 1); + nearest_ref_stop_path_point_index_ = static_cast(path->points.size() - 1); for (const auto & scene_module : scene_modules_) { tier4_planning_msgs::msg::StopReason stop_reason; std::shared_ptr traffic_light_scene_module( @@ -85,8 +85,8 @@ void TrafficLightModuleManager::modifyPathVelocity( } if ( traffic_light_scene_module->getFirstRefStopPathPointIndex() < - first_ref_stop_path_point_index_) { - first_ref_stop_path_point_index_ = + nearest_ref_stop_path_point_index_) { + nearest_ref_stop_path_point_index_ = traffic_light_scene_module->getFirstRefStopPathPointIndex(); if ( traffic_light_scene_module->getTrafficLightModuleState() != @@ -126,14 +126,14 @@ void TrafficLightModuleManager::launchNewModules( // Use lanelet_id to unregister module when the route is changed const auto lane_id = traffic_light_reg_elem.second.id(); - const auto module_id = lane_id; - if (!isModuleRegisteredFromExistingAssociatedModule(module_id)) { + if (!isModuleRegisteredFromExistingAssociatedModule(lane_id)) { registerModule(std::make_shared( - module_id, lane_id, *(traffic_light_reg_elem.first), traffic_light_reg_elem.second, - planner_param_, logger_.get_child("traffic_light_module"), clock_)); - generateUUID(module_id); + lane_id, *(traffic_light_reg_elem.first), traffic_light_reg_elem.second, planner_param_, + logger_.get_child("traffic_light_module"), clock_)); + generateUUID(lane_id); updateRTCStatus( - getUUID(module_id), true, std::numeric_limits::lowest(), path.header.stamp); + getUUID(lane_id), true, State::WAITING_FOR_EXECUTION, std::numeric_limits::lowest(), + path.header.stamp); } } } @@ -145,9 +145,10 @@ TrafficLightModuleManager::getModuleExpiredFunction( const auto lanelet_id_set = planning_utils::getLaneletIdSetOnPath( path, planner_data_->route_handler_->getLaneletMapPtr(), planner_data_->current_odometry->pose); - return [this, lanelet_id_set](const std::shared_ptr & scene_module) { + return [this, lanelet_id_set]( + [[maybe_unused]] const std::shared_ptr & scene_module) { for (const auto & id : lanelet_id_set) { - if (isModuleRegisteredFromRegElement(id, scene_module->getModuleId())) { + if (isModuleRegisteredFromExistingAssociatedModule(id)) { return false; } } @@ -155,23 +156,6 @@ TrafficLightModuleManager::getModuleExpiredFunction( }; } -bool TrafficLightModuleManager::isModuleRegisteredFromRegElement( - const lanelet::Id & id, const size_t module_id) const -{ - const auto lane = planner_data_->route_handler_->getLaneletMapPtr()->laneletLayer.get(id); - - const auto registered_lane = - planner_data_->route_handler_->getLaneletMapPtr()->laneletLayer.get(module_id); - for (const auto & registered_element : registered_lane.regulatoryElementsAs()) { - for (const auto & element : lane.regulatoryElementsAs()) { - if (hasSameTrafficLight(element, registered_element)) { - return true; - } - } - } - return false; -} - bool TrafficLightModuleManager::isModuleRegisteredFromExistingAssociatedModule( const lanelet::Id & id) const { diff --git a/planning/behavior_velocity_traffic_light_module/src/manager.hpp b/planning/behavior_velocity_traffic_light_module/src/manager.hpp index 87213d8a5ed3f..959ef2f91d36c 100644 --- a/planning/behavior_velocity_traffic_light_module/src/manager.hpp +++ b/planning/behavior_velocity_traffic_light_module/src/manager.hpp @@ -58,7 +58,7 @@ class TrafficLightModuleManager : public SceneModuleManagerInterfaceWithRTC // Debug rclcpp::Publisher::SharedPtr pub_tl_state_; - std::optional first_ref_stop_path_point_index_; + std::optional nearest_ref_stop_path_point_index_; }; class TrafficLightModulePlugin : public PluginWrapper diff --git a/planning/behavior_velocity_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_traffic_light_module/src/scene.cpp index 413ce78beacee..0158251bb42b4 100644 --- a/planning/behavior_velocity_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_traffic_light_module/src/scene.cpp @@ -162,11 +162,10 @@ bool calcStopPointAndInsertIndex( } // namespace TrafficLightModule::TrafficLightModule( - const int64_t module_id, const int64_t lane_id, - const lanelet::TrafficLight & traffic_light_reg_elem, lanelet::ConstLanelet lane, - const PlannerParam & planner_param, const rclcpp::Logger logger, + const int64_t lane_id, const lanelet::TrafficLight & traffic_light_reg_elem, + lanelet::ConstLanelet lane, const PlannerParam & planner_param, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock) -: SceneModuleInterface(module_id, logger, clock), +: SceneModuleInterface(lane_id, logger, clock), lane_id_(lane_id), traffic_light_reg_elem_(traffic_light_reg_elem), lane_(lane), @@ -365,7 +364,7 @@ bool TrafficLightModule::findValidTrafficSignal(TrafficSignalStamped & valid_tra { // get traffic signal associated with the regulatory element id const auto traffic_signal_stamped_opt = planner_data_->getTrafficSignal( - traffic_light_reg_elem_.id(), true /* traffic light module keeps last observation */); + traffic_light_reg_elem_.id(), false /* traffic light module does not keep last observation */); if (!traffic_signal_stamped_opt) { RCLCPP_WARN_STREAM_ONCE( logger_, "the traffic signal data associated with regulatory element id " diff --git a/planning/behavior_velocity_traffic_light_module/src/scene.hpp b/planning/behavior_velocity_traffic_light_module/src/scene.hpp index 102ddbe2e9fa8..d6a409ca7034a 100644 --- a/planning/behavior_velocity_traffic_light_module/src/scene.hpp +++ b/planning/behavior_velocity_traffic_light_module/src/scene.hpp @@ -66,9 +66,8 @@ class TrafficLightModule : public SceneModuleInterface public: TrafficLightModule( - const int64_t module_id, const int64_t lane_id, - const lanelet::TrafficLight & traffic_light_reg_elem, lanelet::ConstLanelet lane, - const PlannerParam & planner_param, const rclcpp::Logger logger, + const int64_t lane_id, const lanelet::TrafficLight & traffic_light_reg_elem, + lanelet::ConstLanelet lane, const PlannerParam & planner_param, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock); bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; diff --git a/planning/behavior_velocity_virtual_traffic_light_module/CMakeLists.txt b/planning/behavior_velocity_virtual_traffic_light_module/CMakeLists.txt index 48ffa35cbae5e..a1c00cf49db29 100644 --- a/planning/behavior_velocity_virtual_traffic_light_module/CMakeLists.txt +++ b/planning/behavior_velocity_virtual_traffic_light_module/CMakeLists.txt @@ -3,7 +3,7 @@ project(behavior_velocity_virtual_traffic_light_module) find_package(autoware_cmake REQUIRED) autoware_package() -pluginlib_export_plugin_description_file(behavior_velocity_planner plugins.xml) +pluginlib_export_plugin_description_file(autoware_behavior_velocity_planner plugins.xml) ament_auto_add_library(${PROJECT_NAME} SHARED src/debug.cpp diff --git a/planning/behavior_velocity_walkway_module/CMakeLists.txt b/planning/behavior_velocity_walkway_module/CMakeLists.txt index cd41dec991bc6..351a240743402 100644 --- a/planning/behavior_velocity_walkway_module/CMakeLists.txt +++ b/planning/behavior_velocity_walkway_module/CMakeLists.txt @@ -3,7 +3,7 @@ project(behavior_velocity_walkway_module) find_package(autoware_cmake REQUIRED) autoware_package() -pluginlib_export_plugin_description_file(behavior_velocity_planner plugins.xml) +pluginlib_export_plugin_description_file(autoware_behavior_velocity_planner plugins.xml) ament_auto_add_library(${PROJECT_NAME} SHARED src/debug.cpp 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 9c13f14d180d0..2c10b1b491ace 100644 --- a/planning/freespace_planner/include/freespace_planner/freespace_planner_node.hpp +++ b/planning/freespace_planner/include/freespace_planner/freespace_planner_node.hpp @@ -133,6 +133,8 @@ class FreespacePlannerNode : public rclcpp::Node size_t prev_target_index_; 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/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/src/freespace_planner/freespace_planner_node.cpp b/planning/freespace_planner/src/freespace_planner/freespace_planner_node.cpp index bd8045e653a16..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(); } @@ -444,23 +446,42 @@ void FreespacePlannerNode::onTimer() return; } - if (isPlanRequired()) { - // 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)); + // 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, 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(); - // Plan new trajectory - planTrajectory(); + reset_in_progress_ = true; + } + + if (reset_in_progress_) { + const auto is_stopped = isStopped(odom_buffer_, node_param_.th_stopped_velocity_mps); + if (is_stopped) { + // Plan new trajectory + planTrajectory(); + reset_in_progress_ = false; + } else { + // Will keep current stop trajectory + RCLCPP_WARN_THROTTLE( + get_logger(), *get_clock(), 1000, + "Waiting for the vehicle to stop before generating a new trajectory."); + } } // StopTrajectory if (trajectory_.points.size() <= 1) { + is_new_parking_cycle_ = false; return; } @@ -472,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() 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/freespace_planning_algorithms/package.xml b/planning/freespace_planning_algorithms/package.xml index 2fb3e066f0bdd..9b19d8a81bb51 100644 --- a/planning/freespace_planning_algorithms/package.xml +++ b/planning/freespace_planning_algorithms/package.xml @@ -19,6 +19,7 @@ geometry_msgs nav_msgs nlohmann-json-dev + pybind11_vendor rosbag2_cpp std_msgs tf2 diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp index 4bc0f21dd947b..d4f12316052d9 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.cpp @@ -1,4 +1,4 @@ -// Copyright 2019 Autoware Foundation +// Copyright 2019-2024 Autoware Foundation // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -98,7 +98,7 @@ bool is_in_parking_lot( } double project_goal_to_map( - const lanelet::Lanelet & lanelet_component, const lanelet::ConstPoint3d & goal_point) + const lanelet::ConstLanelet & lanelet_component, const lanelet::ConstPoint3d & goal_point) { const lanelet::ConstLineString3d center_line = lanelet::utils::generateFineCenterline(lanelet_component); @@ -182,12 +182,6 @@ bool DefaultPlanner::ready() const void DefaultPlanner::map_callback(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); - shoulder_lanelets_ = lanelet::utils::query::shoulderLanelets(all_lanelets); is_graph_ready_ = true; } @@ -199,7 +193,7 @@ PlannerPlugin::MarkerArray DefaultPlanner::visualize(const LaneletRoute & route) for (const auto & route_section : route.segments) { for (const auto & lane_id : route_section.primitives) { - auto lanelet = lanelet_map_ptr_->laneletLayer.get(lane_id.id); + auto lanelet = route_handler_.getLaneletsFromId(lane_id.id); route_lanelets.push_back(lanelet); if (route_section.preferred_primitive.id == lane_id.id) { goal_lanelets.push_back(lanelet); @@ -274,15 +268,15 @@ bool DefaultPlanner::check_goal_footprint_inside_lanes( if (boost::geometry::within(goal_footprint, combined_prev_lanelet.polygon2d().basicPolygon())) { return true; } - + const auto following = route_handler_.getNextLanelets(current_lanelet); // check if goal footprint is in between many lanelets in depth-first search manner - for (const auto & next_lane : routing_graph_ptr_->following(current_lanelet)) { + for (const auto & next_lane : following) { next_lane_length += lanelet::utils::getLaneletLength2d(next_lane); lanelet::ConstLanelets lanelets; lanelets.push_back(combined_prev_lanelet); lanelets.push_back(next_lane); lanelet::ConstLanelet combined_lanelets = - combine_lanelets_with_shoulder(lanelets, shoulder_lanelets_); + combine_lanelets_with_shoulder(lanelets, route_handler_); // if next lanelet length is longer than vehicle longitudinal offset if (vehicle_info_.max_longitudinal_offset_m + search_margin < next_lane_length) { @@ -317,23 +311,38 @@ bool DefaultPlanner::is_goal_valid( // check if goal is in shoulder lanelet lanelet::Lanelet closest_shoulder_lanelet; + const auto shoulder_lanelets = route_handler_.getShoulderLaneletsAtPose(goal); if (lanelet::utils::query::getClosestLanelet( - shoulder_lanelets_, goal, &closest_shoulder_lanelet)) { - if (is_in_lane(closest_shoulder_lanelet, goal_lanelet_pt)) { - const auto lane_yaw = - lanelet::utils::getLaneletAngle(closest_shoulder_lanelet, goal.position); - const auto goal_yaw = tf2::getYaw(goal.orientation); - const auto angle_diff = tier4_autoware_utils::normalizeRadian(lane_yaw - goal_yaw); - const double th_angle = tier4_autoware_utils::deg2rad(param_.goal_angle_threshold_deg); - if (std::abs(angle_diff) < th_angle) { - return true; - } + shoulder_lanelets, goal, &closest_shoulder_lanelet)) { + const auto lane_yaw = lanelet::utils::getLaneletAngle(closest_shoulder_lanelet, goal.position); + const auto goal_yaw = tf2::getYaw(goal.orientation); + const auto angle_diff = tier4_autoware_utils::normalizeRadian(lane_yaw - goal_yaw); + const double th_angle = tier4_autoware_utils::deg2rad(param_.goal_angle_threshold_deg); + if (std::abs(angle_diff) < th_angle) { + return true; } } - - lanelet::Lanelet closest_lanelet; - if (!lanelet::utils::query::getClosestLanelet(road_lanelets_, goal, &closest_lanelet)) { - return false; + lanelet::ConstLanelet closest_lanelet; + const auto road_lanelets_at_goal = route_handler_.getRoadLaneletsAtPose(goal); + if (!lanelet::utils::query::getClosestLanelet(road_lanelets_at_goal, goal, &closest_lanelet)) { + // if no road lanelets directly at the goal, find the closest one + const lanelet::BasicPoint2d goal_point{goal.position.x, goal.position.y}; + auto closest_dist = std::numeric_limits::max(); + const auto closest_road_lanelet_found = + route_handler_.getLaneletMapPtr()->laneletLayer.nearestUntil( + goal_point, [&](const auto & bbox, const auto & ll) { + // this search is done by increasing distance between the bounding box and the goal + // we stop the search when the bounding box is further than the closest dist found + if (lanelet::geometry::distance2d(bbox, goal_point) > closest_dist) + return true; // stop the search + const auto dist = lanelet::geometry::distance2d(goal_point, ll.polygon2d()); + if (route_handler_.isRoadLanelet(ll) && dist < closest_dist) { + closest_dist = dist; + closest_lanelet = ll; + } + return false; // continue the search + }); + if (!closest_road_lanelet_found) return false; } const auto local_vehicle_footprint = vehicle_info_.createFootprint(); @@ -345,7 +354,7 @@ bool DefaultPlanner::is_goal_valid( double next_lane_length = 0.0; // combine calculated route lanelets const lanelet::ConstLanelet combined_prev_lanelet = - combine_lanelets_with_shoulder(path_lanelets, shoulder_lanelets_); + combine_lanelets_with_shoulder(path_lanelets, route_handler_); // check if goal footprint exceeds lane when the goal isn't in parking_lot if ( @@ -353,7 +362,7 @@ bool DefaultPlanner::is_goal_valid( !check_goal_footprint_inside_lanes( closest_lanelet, combined_prev_lanelet, polygon_footprint, next_lane_length) && !is_in_parking_lot( - lanelet::utils::query::getAllParkingLots(lanelet_map_ptr_), + lanelet::utils::query::getAllParkingLots(route_handler_.getLaneletMapPtr()), lanelet::utils::conversion::toLaneletPoint(goal.position))) { RCLCPP_WARN(logger, "Goal's footprint exceeds lane!"); return false; @@ -371,13 +380,15 @@ bool DefaultPlanner::is_goal_valid( } // check if goal is in parking space - const auto parking_spaces = lanelet::utils::query::getAllParkingSpaces(lanelet_map_ptr_); + const auto parking_spaces = + lanelet::utils::query::getAllParkingSpaces(route_handler_.getLaneletMapPtr()); if (is_in_parking_space(parking_spaces, goal_lanelet_pt)) { return true; } // check if goal is in parking lot - const auto parking_lots = lanelet::utils::query::getAllParkingLots(lanelet_map_ptr_); + const auto parking_lots = + lanelet::utils::query::getAllParkingLots(route_handler_.getLaneletMapPtr()); if (is_in_parking_lot(parking_lots, goal_lanelet_pt)) { return true; } @@ -424,7 +435,8 @@ PlannerPlugin::LaneletRoute DefaultPlanner::plan(const RoutePoints & points) auto goal_pose = points.back(); if (param_.enable_correct_goal_pose) { goal_pose = get_closest_centerline_pose( - lanelet::utils::query::laneletLayer(lanelet_map_ptr_), goal_pose, vehicle_info_); + lanelet::utils::query::laneletLayer(route_handler_.getLaneletMapPtr()), goal_pose, + vehicle_info_); } if (!is_goal_valid(goal_pose, all_route_lanelets)) { @@ -451,7 +463,7 @@ geometry_msgs::msg::Pose DefaultPlanner::refine_goal_height( const Pose & goal, const RouteSections & route_sections) { const auto goal_lane_id = route_sections.back().preferred_primitive.id; - lanelet::Lanelet goal_lanelet = lanelet_map_ptr_->laneletLayer.get(goal_lane_id); + const auto goal_lanelet = route_handler_.getLaneletsFromId(goal_lane_id); const auto goal_lanelet_pt = lanelet::utils::conversion::toLaneletPoint(goal.position); const auto goal_height = project_goal_to_map(goal_lanelet, goal_lanelet_pt); diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp index 9f1a9d206e376..8c0fbf3b33955 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp @@ -48,6 +48,8 @@ class DefaultPlanner : public mission_planner::PlannerPlugin void initialize(rclcpp::Node * node, const HADMapBin::ConstSharedPtr msg) override; bool ready() const override; LaneletRoute plan(const RoutePoints & points) override; + void updateRoute(const PlannerPlugin::LaneletRoute & route) override; + void clearRoute() override; MarkerArray visualize(const LaneletRoute & route) const override; MarkerArray visualize_debug_footprint(tier4_autoware_utils::LinearRing2d goal_footprint_) const; vehicle_info_util::VehicleInfo vehicle_info_; @@ -56,11 +58,6 @@ class DefaultPlanner : public mission_planner::PlannerPlugin using RouteSections = std::vector; using Pose = geometry_msgs::msg::Pose; bool is_graph_ready_; - lanelet::LaneletMapPtr lanelet_map_ptr_; - lanelet::routing::RoutingGraphPtr routing_graph_ptr_; - lanelet::traffic_rules::TrafficRulesPtr traffic_rules_ptr_; - lanelet::ConstLanelets road_lanelets_; - lanelet::ConstLanelets shoulder_lanelets_; route_handler::RouteHandler route_handler_; DefaultPlannerParameters param_; @@ -102,9 +99,6 @@ class DefaultPlanner : public mission_planner::PlannerPlugin * route_sections) and return the z-aligned goal position */ Pose refine_goal_height(const Pose & goal, const RouteSections & route_sections); - - void updateRoute(const PlannerPlugin::LaneletRoute & route); - void clearRoute(); }; } // namespace mission_planner::lanelet2 diff --git a/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp b/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp index 4ef4bd6f20ed0..e7797946aa619 100644 --- a/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp @@ -1,4 +1,4 @@ -// Copyright 2019 Autoware Foundation +// Copyright 2019-2024 Autoware Foundation // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -42,7 +42,7 @@ void insert_marker_array( } lanelet::ConstLanelet combine_lanelets_with_shoulder( - const lanelet::ConstLanelets & lanelets, const lanelet::ConstLanelets & shoulder_lanelets) + const lanelet::ConstLanelets & lanelets, const route_handler::RouteHandler & route_handler) { lanelet::Points3d lefts; lanelet::Points3d rights; @@ -57,30 +57,18 @@ lanelet::ConstLanelet combine_lanelets_with_shoulder( } } + // lambda to add bound to target_bound + const auto add_bound = [](const auto & bound, auto & target_bound) { + std::transform( + bound.begin(), bound.end(), std::back_inserter(target_bound), + [](const auto & pt) { return lanelet::Point3d(pt); }); + }; for (const auto & llt : lanelets) { - // lambda to check if shoulder lane which share left bound with lanelets exist - const auto find_bound_shared_shoulder = - [&shoulder_lanelets](const auto & lanelet_bound, const auto & get_shoulder_bound) { - return std::find_if( - shoulder_lanelets.begin(), shoulder_lanelets.end(), - [&lanelet_bound, &get_shoulder_bound](const auto & shoulder_llt) { - return lanelet_bound.id() == get_shoulder_bound(shoulder_llt).id(); - }); - }; - - // lambda to add bound to target_bound - const auto add_bound = [](const auto & bound, auto & target_bound) { - std::transform( - bound.begin(), bound.end(), std::back_inserter(target_bound), - [](const auto & pt) { return lanelet::Point3d(pt); }); - }; - // check if shoulder lanelets which has RIGHT bound same to LEFT bound of lanelet exist - const auto left_shared_shoulder_it = find_bound_shared_shoulder( - llt.leftBound(), [](const auto & shoulder_llt) { return shoulder_llt.rightBound(); }); - if (left_shared_shoulder_it != shoulder_lanelets.end()) { + const auto left_shared_shoulder = route_handler.getLeftShoulderLanelet(llt); + if (left_shared_shoulder) { // if exist, add left bound of SHOULDER lanelet to lefts - add_bound(left_shared_shoulder_it->leftBound(), lefts); + add_bound(left_shared_shoulder->leftBound(), lefts); } else if ( // if not exist, add left bound of lanelet to lefts // if the **left** of this lanelet does not match any of the **right** bounds of `lanelets`, @@ -90,11 +78,10 @@ lanelet::ConstLanelet combine_lanelets_with_shoulder( } // check if shoulder lanelets which has LEFT bound same to RIGHT bound of lanelet exist - const auto right_shared_shoulder_it = find_bound_shared_shoulder( - llt.rightBound(), [](const auto & shoulder_llt) { return shoulder_llt.leftBound(); }); - if (right_shared_shoulder_it != shoulder_lanelets.end()) { + const auto right_shared_shoulder = route_handler.getRightShoulderLanelet(llt); + if (right_shared_shoulder) { // if exist, add right bound of SHOULDER lanelet to rights - add_bound(right_shared_shoulder_it->rightBound(), rights); + add_bound(right_shared_shoulder->rightBound(), rights); } else if ( // if not exist, add right bound of lanelet to rights // if the **right** of this lanelet does not match any of the **left** bounds of `lanelets`, diff --git a/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp b/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp index 3eb38638e17b7..428cd979a2526 100644 --- a/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp +++ b/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp @@ -1,4 +1,4 @@ -// Copyright 2019 Autoware Foundation +// Copyright 2019-2024 Autoware Foundation // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -16,6 +16,7 @@ #define LANELET2_PLUGINS__UTILITY_FUNCTIONS_HPP_ #include +#include #include #include @@ -50,10 +51,10 @@ void insert_marker_array( * @brief create a single merged lanelet whose left/right bounds consist of the leftmost/rightmost * bound of the original lanelets or the left/right bound of its adjacent road_shoulder respectively * @param lanelets topologically sorted sequence of lanelets - * @param shoulder_lanelets list of possible road_shoulder lanelets to combine with lanelets + * @param route_handler route handler to query the lanelet map */ lanelet::ConstLanelet combine_lanelets_with_shoulder( - const lanelet::ConstLanelets & lanelets, const lanelet::ConstLanelets & shoulder_lanelets); + const lanelet::ConstLanelets & lanelets, const route_handler::RouteHandler & route_handler); std::vector convertCenterlineToPoints(const lanelet::Lanelet & lanelet); geometry_msgs::msg::Pose convertBasicPoint3dToPose( diff --git a/planning/mission_planner/src/mission_planner/mission_planner.cpp b/planning/mission_planner/src/mission_planner/mission_planner.cpp index e9a0108cdaa24..af363bcf23da7 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.cpp @@ -87,6 +87,17 @@ MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options) logger_configure_ = std::make_unique(this); } +void MissionPlanner::publish_pose_log(const Pose & pose, const std::string & pose_type) +{ + const auto & p = pose.position; + RCLCPP_INFO( + this->get_logger(), "%s pose - x: %f, y: %f, z: %f", pose_type.c_str(), p.x, p.y, p.z); + const auto & quaternion = pose.orientation; + RCLCPP_INFO( + this->get_logger(), "%s orientation - qx: %f, qy: %f, qz: %f, qw: %f", pose_type.c_str(), + quaternion.x, quaternion.y, quaternion.z, quaternion.w); +} + void MissionPlanner::check_initialization() { auto logger = get_logger(); @@ -239,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."); } @@ -247,6 +258,9 @@ void MissionPlanner::on_set_lanelet_route( change_route(route); change_state(RouteState::SET); res->status.success = true; + + publish_pose_log(odometry_->pose.pose, "initial"); + publish_pose_log(req->goal_pose, "goal"); } void MissionPlanner::on_set_waypoint_route( @@ -284,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."); } @@ -292,6 +306,9 @@ void MissionPlanner::on_set_waypoint_route( change_route(route); change_state(RouteState::SET); res->status.success = true; + + publish_pose_log(odometry_->pose.pose, "initial"); + publish_pose_log(req->goal_pose, "goal"); } void MissionPlanner::change_route() diff --git a/planning/mission_planner/src/mission_planner/mission_planner.hpp b/planning/mission_planner/src/mission_planner/mission_planner.hpp index 8016851d5a7d3..6752ceb4eaa8b 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.hpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.hpp @@ -122,6 +122,8 @@ class MissionPlanner : public rclcpp::Node const Header & header, const std::vector & waypoints, const Pose & goal_pose, const UUID & uuid, const bool allow_goal_modification); + void publish_pose_log(const Pose & pose, const std::string & pose_type); + rclcpp::TimerBase::SharedPtr data_check_timer_; void check_initialization(); diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/CMakeLists.txt b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/CMakeLists.txt new file mode 100644 index 0000000000000..b96ca3017a031 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/CMakeLists.txt @@ -0,0 +1,23 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_motion_velocity_out_of_lane_module) + +find_package(autoware_cmake REQUIRED) +autoware_package() +pluginlib_export_plugin_description_file(autoware_motion_velocity_planner_node plugins.xml) + +ament_auto_add_library(${PROJECT_NAME} SHARED + DIRECTORY src +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + ament_add_ros_isolated_gtest(test_${PROJECT_NAME} + test/test_filter_predicted_objects.cpp + ) + target_link_libraries(test_${PROJECT_NAME} + ${PROJECT_NAME} + ) +endif() + +ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/README.md b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/README.md new file mode 100644 index 0000000000000..99396eb0edf22 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/README.md @@ -0,0 +1,165 @@ +## Out of Lane + +### Role + +`out_of_lane` is the module that decelerates and stops to prevent the ego vehicle from entering another lane with incoming dynamic objects. + +### Activation Timing + +This module is activated if `launch_out_of_lane` is set to true. + +### Inner-workings / Algorithms + +The algorithm is made of the following steps. + +1. Calculate the ego path footprints (red). +2. Calculate the other lanes (magenta). +3. Calculate the overlapping ranges between the ego path footprints and the other lanes (green). +4. For each overlapping range, decide if a stop or slow down action must be taken. +5. For each action, insert the corresponding stop or slow down point in the path. + +![overview](./docs/out_of_lane-footprints_other_lanes_overlaps_ranges.png) + +#### 1. Ego Path Footprints + +In this first step, the ego footprint is projected at each path point and are eventually inflated based on the `extra_..._offset` parameters. + +#### 2. Other lanes + +In the second step, the set of lanes to consider for overlaps is generated. +This set is built by selecting all lanelets within some distance from the ego vehicle, and then removing non-relevant lanelets. +The selection distance is chosen as the maximum between the `slowdown.distance_threshold` and the `stop.distance_threshold`. + +A lanelet is deemed non-relevant if it meets one of the following conditions. + +- It is part of the lanelets followed by the ego path. +- It contains the rear point of the ego footprint. +- It follows one of the ego path lanelets. + +#### 3. Overlapping ranges + +In the third step, overlaps between the ego path footprints and the other lanes are calculated. +For each pair of other lane $l$ and ego path footprint $f$, we calculate the overlapping polygons using `boost::geometry::intersection`. +For each overlapping polygon found, if the distance inside the other lane $l$ is above the `overlap.minimum_distance` threshold, then the overlap is ignored. +Otherwise, the arc length range (relative to the ego path) and corresponding points of the overlapping polygons are stored. +Ultimately, for each other lane $l$, overlapping ranges of successive overlaps are built with the following information: + +- overlapped other lane $l$. +- start and end ego path indexes. +- start and end ego path arc lengths. +- start and end overlap points. + +#### 4. Decisions + +In the fourth step, a decision to either slow down or stop before each overlapping range is taken based on the dynamic objects. +The conditions for the decision depend on the value of the `mode` parameter. + +Whether it is decided to slow down or stop is determined by the distance between the ego vehicle and the start of the overlapping range (in arc length along the ego path). +If this distance is bellow the `actions.slowdown.threshold`, a velocity of `actions.slowdown.velocity` will be used. +If the distance is bellow the `actions.stop.threshold`, a velocity of `0`m/s will be used. + + + + + + +
+ + + +
+ +##### Threshold + +With the `mode` set to `"threshold"`, +a decision to stop or slow down before a range is made if +an incoming dynamic object is estimated to reach the overlap within `threshold.time_threshold`. + +##### TTC (time to collision) + +With the `mode` set to `"ttc"`, +estimates for the times when ego and the dynamic objects reach the start and end of the overlapping range are calculated. +This is then used to calculate the time to collision over the period where ego crosses the overlap. +If the time to collision is predicted to go bellow the `ttc.threshold`, the decision to stop or slow down is made. + +##### Intervals + +With the `mode` set to `"intervals"`, +the estimated times when ego and the dynamic objects reach the start and end points of +the overlapping range are used to create time intervals. +These intervals can be made shorter or longer using the +`intervals.ego_time_buffer` and `intervals.objects_time_buffer` parameters. +If the time interval of ego overlaps with the time interval of an object, the decision to stop or slow down is made. + +##### Time estimates + +###### Ego + +To estimate the times when ego will reach an overlap, it is assumed that ego travels along its path +at its current velocity or at half the velocity of the path points, whichever is higher. + +###### Dynamic objects + +Two methods are used to estimate the time when a dynamic objects with reach some point. +If `objects.use_predicted_paths` is set to `true`, the predicted paths of the dynamic object are used if their confidence value is higher than the value set by the `objects.predicted_path_min_confidence` parameter. +Otherwise, the lanelet map is used to estimate the distance between the object and the point and the time is calculated assuming the object keeps its current velocity. + +#### 5. Path update + +Finally, for each decision to stop or slow down before an overlapping range, +a point is inserted in the path. +For a decision taken for an overlapping range with a lane $l$ starting at ego path point index $i$, +a point is inserted in the path between index $i$ and $i-1$ such that the ego footprint projected at the inserted point does not overlap $l$. +Such point with no overlap must exist since, by definition of the overlapping range, +we know that there is no overlap at $i-1$. + +If the point would cause a higher deceleration than allowed by the `max_accel` parameter (node parameter), +it is skipped. + +Moreover, parameter `action.distance_buffer` adds an extra distance between the ego footprint and the overlap when possible. + +### Module Parameters + +| Parameter | Type | Description | +| ----------------------------- | ------ | --------------------------------------------------------------------------------- | +| `mode` | string | [-] mode used to consider a dynamic object. Candidates: threshold, intervals, ttc | +| `skip_if_already_overlapping` | bool | [-] if true, do not run this module when ego already overlaps another lane | + +| Parameter /threshold | Type | Description | +| -------------------- | ------ | ---------------------------------------------------------------- | +| `time_threshold` | double | [s] consider objects that will reach an overlap within this time | + +| Parameter /intervals | Type | Description | +| --------------------- | ------ | ------------------------------------------------------- | +| `ego_time_buffer` | double | [s] extend the ego time interval by this buffer | +| `objects_time_buffer` | double | [s] extend the time intervals of objects by this buffer | + +| Parameter /ttc | Type | Description | +| -------------- | ------ | ------------------------------------------------------------------------------------------------------ | +| `threshold` | double | [s] consider objects with an estimated time to collision bellow this value while ego is on the overlap | + +| Parameter /objects | Type | Description | +| ------------------------------- | ------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `minimum_velocity` | double | [m/s] ignore objects with a velocity lower than this value | +| `predicted_path_min_confidence` | double | [-] minimum confidence required for a predicted path to be considered | +| `use_predicted_paths` | bool | [-] if true, use the predicted paths to estimate future positions; if false, assume the object moves at constant velocity along _all_ lanelets it currently is located in | + +| Parameter /overlap | Type | Description | +| ------------------ | ------ | ---------------------------------------------------------------------------------------------------- | +| `minimum_distance` | double | [m] minimum distance inside a lanelet for an overlap to be considered | +| `extra_length` | double | [m] extra arc length to add to the front and back of an overlap (used to calculate enter/exit times) | + +| Parameter /action | Type | Description | +| ----------------------------- | ------ | ---------------------------------------------------------------------------------------------- | +| `skip_if_over_max_decel` | bool | [-] if true, do not take an action that would cause more deceleration than the maximum allowed | +| `distance_buffer` | double | [m] buffer distance to try to keep between the ego footprint and lane | +| `slowdown.distance_threshold` | double | [m] insert a slow down when closer than this distance from an overlap | +| `slowdown.velocity` | double | [m] slow down velocity | +| `stop.distance_threshold` | double | [m] insert a stop when closer than this distance from an overlap | + +| Parameter /ego | Type | Description | +| -------------------- | ------ | ---------------------------------------------------- | +| `extra_front_offset` | double | [m] extra front distance to add to the ego footprint | +| `extra_rear_offset` | double | [m] extra rear distance to add to the ego footprint | +| `extra_left_offset` | double | [m] extra left distance to add to the ego footprint | +| `extra_right_offset` | double | [m] extra right distance to add to the ego footprint | diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml new file mode 100644 index 0000000000000..e57b5a45d8be6 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/config/out_of_lane.param.yaml @@ -0,0 +1,43 @@ +/**: + ros__parameters: + 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 + + threshold: + time_threshold: 5.0 # [s] consider objects that will reach an overlap within this time + intervals: # consider objects if their estimated time interval spent on the overlap intersect the estimated time interval of ego + ego_time_buffer: 0.5 # [s] extend the ego time interval by this buffer + objects_time_buffer: 0.5 # [s] extend the time intervals of objects by this buffer + ttc: + threshold: 3.0 # [s] consider objects with an estimated time to collision bellow this value while on the overlap + + objects: + minimum_velocity: 0.5 # [m/s] objects lower than this velocity will be ignored + use_predicted_paths: true # if true, use the predicted paths to estimate future positions. + # if false, assume the object moves at constant velocity along *all* lanelets it currently is located in. + predicted_path_min_confidence : 0.1 # when using predicted paths, ignore the ones whose confidence is lower than this value. + distance_buffer: 1.0 # [m] distance buffer used to determine if a collision will occur in the other lane + cut_predicted_paths_beyond_red_lights: true # if true, predicted paths are cut beyond the stop line of red traffic lights + + overlap: + minimum_distance: 0.0 # [m] minimum distance inside a lanelet for an overlap to be considered + extra_length: 0.0 # [m] extra arc length to add to the front and back of an overlap (used to calculate enter/exit times) + + action: # action to insert in the trajectory if an object causes a conflict at an overlap + skip_if_over_max_decel: true # if true, do not take an action that would cause more deceleration than the maximum allowed + precision: 0.1 # [m] precision when inserting a stop pose in the trajectory + distance_buffer: 1.5 # [m] buffer distance to try to keep between the ego footprint and lane + min_duration: 1.0 # [s] minimum duration needed before a decision can be canceled + slowdown: + distance_threshold: 30.0 # [m] insert a slowdown when closer than this distance from an overlap + velocity: 2.0 # [m/s] slowdown velocity + stop: + distance_threshold: 15.0 # [m] insert a stop when closer than this distance from an overlap + + ego: + min_assumed_velocity: 2.0 # [m/s] minimum velocity used to calculate the enter and exit times of ego + extra_front_offset: 0.0 # [m] extra front distance + extra_rear_offset: 0.0 # [m] extra rear distance + extra_right_offset: 0.0 # [m] extra right distance + extra_left_offset: 0.0 # [m] extra left distance diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane-footprints_other_lanes_overlaps_ranges.png b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane-footprints_other_lanes_overlaps_ranges.png new file mode 100644 index 0000000000000..f095467b3b0ac Binary files /dev/null and b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane-footprints_other_lanes_overlaps_ranges.png differ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_slow.png b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_slow.png new file mode 100644 index 0000000000000..2f358975b9491 Binary files /dev/null and b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_slow.png differ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_stop.png b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_stop.png new file mode 100644 index 0000000000000..fdb75ac0c6eb8 Binary files /dev/null and b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/docs/out_of_lane_stop.png differ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml new file mode 100644 index 0000000000000..5ba740773d5a5 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml @@ -0,0 +1,41 @@ + + + + autoware_motion_velocity_out_of_lane_module + 0.1.0 + The motion_velocity_out_of_lane_module package + + Maxime Clement + Tomoya Kimura + Shumpei Wakabayashi + Takayuki Murooka + + Apache License 2.0 + + autoware_cmake + + autoware_auto_perception_msgs + autoware_auto_planning_msgs + autoware_motion_velocity_planner_common + geometry_msgs + lanelet2_extension + libboost-dev + motion_utils + pluginlib + rclcpp + route_handler + tf2 + tier4_autoware_utils + tier4_planning_msgs + traffic_light_utils + vehicle_info_util + visualization_msgs + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/plugins.xml b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/plugins.xml new file mode 100644 index 0000000000000..0a05163e8f1d0 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/plugins.xml @@ -0,0 +1,3 @@ + + + diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp new file mode 100644 index 0000000000000..157d545dcac0d --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp @@ -0,0 +1,85 @@ +// 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 "calculate_slowdown_points.hpp" + +#include "footprint.hpp" + +#include +#include + +#include + +#include + +namespace autoware::motion_velocity_planner::out_of_lane +{ + +bool can_decelerate( + const EgoData & ego_data, const TrajectoryPoint & point, const double target_vel) +{ + // TODO(Maxime): use the library function + const auto dist_ahead_of_ego = motion_utils::calcSignedArcLength( + ego_data.trajectory_points, ego_data.pose.position, point.pose.position); + const auto acc_to_target_vel = + (ego_data.velocity * ego_data.velocity - target_vel * target_vel) / (2 * dist_ahead_of_ego); + return acc_to_target_vel < std::abs(ego_data.max_decel); +} + +std::optional calculate_last_in_lane_pose( + const EgoData & ego_data, const Slowdown & decision, + const tier4_autoware_utils::Polygon2d & footprint, + const std::optional & prev_slowdown_point, const PlannerParam & params) +{ + const auto from_arc_length = + motion_utils::calcSignedArcLength(ego_data.trajectory_points, 0, ego_data.first_trajectory_idx); + const auto to_arc_length = motion_utils::calcSignedArcLength( + ego_data.trajectory_points, 0, decision.target_trajectory_idx); + TrajectoryPoint interpolated_point; + for (auto l = to_arc_length - params.precision; l > from_arc_length; l -= params.precision) { + // TODO(Maxime): binary search + interpolated_point.pose = motion_utils::calcInterpolatedPose(ego_data.trajectory_points, l); + const auto respect_decel_limit = + !params.skip_if_over_max_decel || prev_slowdown_point || + can_decelerate(ego_data, interpolated_point, decision.velocity); + const auto interpolated_footprint = project_to_pose(footprint, interpolated_point.pose); + const auto is_overlap_lane = boost::geometry::overlaps( + interpolated_footprint, decision.lane_to_avoid.polygon2d().basicPolygon()); + const auto is_overlap_extra_lane = + prev_slowdown_point && + boost::geometry::overlaps( + interpolated_footprint, + prev_slowdown_point->slowdown.lane_to_avoid.polygon2d().basicPolygon()); + if (respect_decel_limit && !is_overlap_lane && !is_overlap_extra_lane) + return interpolated_point; + } + return std::nullopt; +} + +std::optional calculate_slowdown_point( + const EgoData & ego_data, const std::vector & decisions, + const std::optional prev_slowdown_point, PlannerParam params) +{ + params.extra_front_offset += params.dist_buffer; + const auto base_footprint = make_base_footprint(params); + + // search for the first slowdown decision for which a stop point can be inserted + for (const auto & decision : decisions) { + const auto last_in_lane_pose = + calculate_last_in_lane_pose(ego_data, decision, base_footprint, prev_slowdown_point, params); + if (last_in_lane_pose) return SlowdownToInsert{decision, *last_in_lane_pose}; + } + return std::nullopt; +} +} // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp new file mode 100644 index 0000000000000..19ed066548d0f --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp @@ -0,0 +1,58 @@ +// 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 CALCULATE_SLOWDOWN_POINTS_HPP_ +#define CALCULATE_SLOWDOWN_POINTS_HPP_ + +#include "types.hpp" + +#include + +#include +#include + +namespace autoware::motion_velocity_planner::out_of_lane +{ + +/// @brief estimate whether ego can decelerate without breaking the deceleration limit +/// @details assume ego wants to reach the target point at the target velocity +/// @param [in] ego_data ego data +/// @param [in] point target point +/// @param [in] target_vel target_velocity +bool can_decelerate( + const EgoData & ego_data, const TrajectoryPoint & point, const double target_vel); + +/// @brief calculate the last pose along the trajectory where ego does not overlap the lane to avoid +/// @param [in] ego_data ego data +/// @param [in] decision the input decision (i.e., which lane to avoid and at what speed) +/// @param [in] footprint the ego footprint +/// @param [in] prev_slowdown_point previous slowdown point. If set, ignore deceleration limits +/// @param [in] params parameters +/// @return the last pose that is not out of lane (if found) +std::optional calculate_last_in_lane_pose( + const EgoData & ego_data, const Slowdown & decision, + const tier4_autoware_utils::Polygon2d & footprint, + const std::optional & prev_slowdown_point, const PlannerParam & params); + +/// @brief calculate the slowdown point to insert in the trajectory +/// @param ego_data ego data (trajectory, velocity, etc) +/// @param decisions decision (before which point to stop, what lane to avoid entering, etc) +/// @param prev_slowdown_point previously calculated slowdown point +/// @param params parameters +/// @return optional slowdown point to insert in the trajectory +std::optional calculate_slowdown_point( + const EgoData & ego_data, const std::vector & decisions, + const std::optional prev_slowdown_point, PlannerParam params); +} // namespace autoware::motion_velocity_planner::out_of_lane +#endif // CALCULATE_SLOWDOWN_POINTS_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.cpp new file mode 100644 index 0000000000000..585f4760290ef --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.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 "debug.hpp" + +#include "types.hpp" + +#include + +#include + +#include +#include + +namespace autoware::motion_velocity_planner::out_of_lane::debug +{ +namespace +{ + +visualization_msgs::msg::Marker get_base_marker() +{ + visualization_msgs::msg::Marker base_marker; + base_marker.header.frame_id = "map"; + base_marker.header.stamp = rclcpp::Time(0); + base_marker.id = 0; + base_marker.type = visualization_msgs::msg::Marker::LINE_STRIP; + base_marker.action = visualization_msgs::msg::Marker::ADD; + base_marker.pose.position = tier4_autoware_utils::createMarkerPosition(0.0, 0.0, 0); + base_marker.pose.orientation = tier4_autoware_utils::createMarkerOrientation(0, 0, 0, 1.0); + base_marker.scale = tier4_autoware_utils::createMarkerScale(0.1, 0.1, 0.1); + base_marker.color = tier4_autoware_utils::createMarkerColor(1.0, 0.1, 0.1, 0.5); + return base_marker; +} +void add_footprint_markers( + visualization_msgs::msg::MarkerArray & debug_marker_array, + const lanelet::BasicPolygons2d & footprints, const double z, const size_t prev_nb) +{ + auto debug_marker = get_base_marker(); + debug_marker.ns = "footprints"; + for (const auto & f : footprints) { + debug_marker.points.clear(); + for (const auto & p : f) + debug_marker.points.push_back( + tier4_autoware_utils::createMarkerPosition(p.x(), p.y(), z + 0.5)); + debug_marker.points.push_back(debug_marker.points.front()); + debug_marker_array.markers.push_back(debug_marker); + debug_marker.id++; + debug_marker.points.clear(); + } + for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) + debug_marker_array.markers.push_back(debug_marker); +} + +void add_current_overlap_marker( + visualization_msgs::msg::MarkerArray & debug_marker_array, + const lanelet::BasicPolygon2d & current_footprint, + const lanelet::ConstLanelets & current_overlapped_lanelets, const double z, const size_t prev_nb) +{ + auto debug_marker = get_base_marker(); + debug_marker.ns = "current_overlap"; + debug_marker.points.clear(); + for (const auto & p : current_footprint) + debug_marker.points.push_back(tier4_autoware_utils::createMarkerPosition(p.x(), p.y(), z)); + if (!debug_marker.points.empty()) debug_marker.points.push_back(debug_marker.points.front()); + if (current_overlapped_lanelets.empty()) + debug_marker.color = tier4_autoware_utils::createMarkerColor(0.1, 1.0, 0.1, 0.5); + else + debug_marker.color = tier4_autoware_utils::createMarkerColor(1.0, 0.1, 0.1, 0.5); + debug_marker_array.markers.push_back(debug_marker); + debug_marker.id++; + for (const auto & ll : current_overlapped_lanelets) { + debug_marker.points.clear(); + for (const auto & p : ll.polygon3d()) + debug_marker.points.push_back( + tier4_autoware_utils::createMarkerPosition(p.x(), p.y(), p.z() + 0.5)); + debug_marker.points.push_back(debug_marker.points.front()); + debug_marker_array.markers.push_back(debug_marker); + debug_marker.id++; + } + for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) + debug_marker_array.markers.push_back(debug_marker); +} + +void add_lanelet_markers( + visualization_msgs::msg::MarkerArray & debug_marker_array, + const lanelet::ConstLanelets & lanelets, const std::string & ns, + const std_msgs::msg::ColorRGBA & color, const size_t prev_nb) +{ + auto debug_marker = get_base_marker(); + debug_marker.ns = ns; + debug_marker.color = color; + for (const auto & ll : lanelets) { + debug_marker.points.clear(); + + // add a small z offset to draw above the lanelet map + for (const auto & p : ll.polygon3d()) + debug_marker.points.push_back( + tier4_autoware_utils::createMarkerPosition(p.x(), p.y(), p.z() + 0.1)); + debug_marker.points.push_back(debug_marker.points.front()); + debug_marker_array.markers.push_back(debug_marker); + debug_marker.id++; + } + debug_marker.action = debug_marker.DELETE; + for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) + debug_marker_array.markers.push_back(debug_marker); +} + +void add_range_markers( + visualization_msgs::msg::MarkerArray & debug_marker_array, const OverlapRanges & ranges, + const std::vector & trajectory_points, + const size_t first_ego_idx, const double z, const size_t prev_nb) +{ + auto debug_marker = get_base_marker(); + debug_marker.ns = "ranges"; + debug_marker.color = tier4_autoware_utils::createMarkerColor(0.2, 0.9, 0.1, 0.5); + for (const auto & range : ranges) { + debug_marker.points.clear(); + debug_marker.points.push_back( + trajectory_points[first_ego_idx + range.entering_trajectory_idx].pose.position); + debug_marker.points.push_back(tier4_autoware_utils::createMarkerPosition( + range.entering_point.x(), range.entering_point.y(), z)); + for (const auto & overlap : range.debug.overlaps) { + debug_marker.points.push_back(tier4_autoware_utils::createMarkerPosition( + overlap.min_overlap_point.x(), overlap.min_overlap_point.y(), z)); + debug_marker.points.push_back(tier4_autoware_utils::createMarkerPosition( + overlap.max_overlap_point.x(), overlap.max_overlap_point.y(), z)); + } + debug_marker.points.push_back(tier4_autoware_utils::createMarkerPosition( + range.exiting_point.x(), range.exiting_point.y(), z)); + debug_marker.points.push_back( + trajectory_points[first_ego_idx + range.exiting_trajectory_idx].pose.position); + debug_marker_array.markers.push_back(debug_marker); + debug_marker.id++; + } + debug_marker.action = debug_marker.DELETE; + for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) + debug_marker_array.markers.push_back(debug_marker); +} + +void add_decision_markers( + visualization_msgs::msg::MarkerArray & debug_marker_array, const OverlapRanges & ranges, + const double z, const size_t prev_nb) +{ + auto debug_marker = get_base_marker(); + debug_marker.action = debug_marker.ADD; + debug_marker.id = 0; + debug_marker.ns = "decisions"; + debug_marker.color = tier4_autoware_utils::createMarkerColor(0.9, 0.1, 0.1, 1.0); + debug_marker.points.clear(); + for (const auto & range : ranges) { + debug_marker.type = debug_marker.LINE_STRIP; + if (range.debug.decision) { + debug_marker.points.push_back(tier4_autoware_utils::createMarkerPosition( + range.entering_point.x(), range.entering_point.y(), z)); + debug_marker.points.push_back( + range.debug.object->kinematics.initial_pose_with_covariance.pose.position); + } + debug_marker_array.markers.push_back(debug_marker); + debug_marker.points.clear(); + debug_marker.id++; + + debug_marker.type = debug_marker.TEXT_VIEW_FACING; + debug_marker.pose.position.x = range.entering_point.x(); + debug_marker.pose.position.y = range.entering_point.y(); + debug_marker.pose.position.z = z; + std::stringstream ss; + ss << "Ego: " << range.debug.times.ego.enter_time << " - " << range.debug.times.ego.exit_time + << "\n"; + if (range.debug.object) { + debug_marker.pose.position.x += + range.debug.object->kinematics.initial_pose_with_covariance.pose.position.x; + debug_marker.pose.position.y += + range.debug.object->kinematics.initial_pose_with_covariance.pose.position.y; + debug_marker.pose.position.x /= 2; + debug_marker.pose.position.y /= 2; + ss << "Obj: " << range.debug.times.object.enter_time << " - " + << range.debug.times.object.exit_time << "\n"; + } + debug_marker.scale.z = 1.0; + debug_marker.text = ss.str(); + debug_marker_array.markers.push_back(debug_marker); + debug_marker.id++; + } + debug_marker.action = debug_marker.DELETE; + for (; debug_marker.id < static_cast(prev_nb); ++debug_marker.id) { + debug_marker_array.markers.push_back(debug_marker); + } +} +} // namespace +visualization_msgs::msg::MarkerArray create_debug_marker_array(const DebugData & debug_data) +{ + constexpr auto z = 0.0; + visualization_msgs::msg::MarkerArray debug_marker_array; + + debug::add_footprint_markers( + debug_marker_array, debug_data.footprints, z, debug_data.prev_footprints); + debug::add_current_overlap_marker( + debug_marker_array, debug_data.current_footprint, debug_data.current_overlapped_lanelets, z, + debug_data.prev_current_overlapped_lanelets); + debug::add_lanelet_markers( + debug_marker_array, debug_data.trajectory_lanelets, "trajectory_lanelets", + tier4_autoware_utils::createMarkerColor(0.1, 0.1, 1.0, 0.5), + debug_data.prev_trajectory_lanelets); + debug::add_lanelet_markers( + debug_marker_array, debug_data.ignored_lanelets, "ignored_lanelets", + tier4_autoware_utils::createMarkerColor(0.7, 0.7, 0.2, 0.5), debug_data.prev_ignored_lanelets); + debug::add_lanelet_markers( + debug_marker_array, debug_data.other_lanelets, "other_lanelets", + tier4_autoware_utils::createMarkerColor(0.4, 0.4, 0.7, 0.5), debug_data.prev_other_lanelets); + debug::add_range_markers( + debug_marker_array, debug_data.ranges, debug_data.trajectory_points, + debug_data.first_trajectory_idx, z, debug_data.prev_ranges); + debug::add_decision_markers(debug_marker_array, debug_data.ranges, z, debug_data.prev_ranges); + return debug_marker_array; +} + +motion_utils::VirtualWalls create_virtual_walls( + const DebugData & debug_data, const PlannerParam & params) +{ + motion_utils::VirtualWalls virtual_walls; + motion_utils::VirtualWall wall; + wall.text = "out_of_lane"; + wall.longitudinal_offset = params.front_offset; + wall.style = motion_utils::VirtualWallType::slowdown; + for (const auto & slowdown : debug_data.slowdowns) { + wall.pose = slowdown.point.pose; + virtual_walls.push_back(wall); + } + return virtual_walls; +} +} // namespace autoware::motion_velocity_planner::out_of_lane::debug diff --git a/system/mrm_handler/src/mrm_handler/mrm_handler_node.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.hpp similarity index 52% rename from system/mrm_handler/src/mrm_handler/mrm_handler_node.cpp rename to planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.hpp index 4aaab3296f64b..4a5be9dfb07ac 100644 --- a/system/mrm_handler/src/mrm_handler/mrm_handler_node.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/debug.hpp @@ -12,21 +12,20 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "mrm_handler/mrm_handler_core.hpp" +#ifndef DEBUG_HPP_ +#define DEBUG_HPP_ -#include +#include "types.hpp" -#include +#include -int main(int argc, char ** argv) +#include + +namespace autoware::motion_velocity_planner::out_of_lane::debug { - 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(); +visualization_msgs::msg::MarkerArray create_debug_marker_array(const DebugData & debug_data); +motion_utils::VirtualWalls create_virtual_walls( + const DebugData & debug_data, const PlannerParam & params); +} // namespace autoware::motion_velocity_planner::out_of_lane::debug - return 0; -} +#endif // DEBUG_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.cpp new file mode 100644 index 0000000000000..56047e459bf51 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.cpp @@ -0,0 +1,388 @@ +// 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 "decisions.hpp" + +#include +#include +#include +#include + +#include + +#include +#include +#include + +#include +#include +#include +#include +namespace autoware::motion_velocity_planner::out_of_lane +{ +double distance_along_trajectory(const EgoData & ego_data, const size_t target_idx) +{ + return motion_utils::calcSignedArcLength( + ego_data.trajectory_points, ego_data.pose.position, ego_data.first_trajectory_idx + target_idx); +} + +double time_along_trajectory( + const EgoData & ego_data, const size_t target_idx, const double min_velocity) +{ + const auto dist = distance_along_trajectory(ego_data, target_idx); + const auto v = std::max( + std::max(ego_data.velocity, min_velocity), + ego_data.trajectory_points[ego_data.first_trajectory_idx + target_idx] + .longitudinal_velocity_mps * + 0.5); + return dist / v; +} + +bool object_is_incoming( + const lanelet::BasicPoint2d & object_position, + const std::shared_ptr route_handler, + const lanelet::ConstLanelet & lane) +{ + const auto lanelets = route_handler->getPrecedingLaneletSequence(lane, 50.0); + if (boost::geometry::within(object_position, lane.polygon2d().basicPolygon())) return true; + for (const auto & lls : lanelets) + for (const auto & ll : lls) + if (boost::geometry::within(object_position, ll.polygon2d().basicPolygon())) return true; + return false; +} + +std::optional> object_time_to_range( + const autoware_auto_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, + const std::shared_ptr route_handler, const double dist_buffer, + const rclcpp::Logger & logger) +{ + // skip the dynamic object if it is not in a lane preceding the overlapped lane + // lane changes are intentionally not considered + const auto object_point = lanelet::BasicPoint2d( + object.kinematics.initial_pose_with_covariance.pose.position.x, + object.kinematics.initial_pose_with_covariance.pose.position.y); + if (!object_is_incoming(object_point, route_handler, range.lane)) return {}; + + const auto max_deviation = object.shape.dimensions.y + range.inside_distance + dist_buffer; + const auto max_lon_deviation = object.shape.dimensions.x / 2.0; + auto worst_enter_time = std::optional(); + auto worst_exit_time = std::optional(); + + for (const auto & predicted_path : object.kinematics.predicted_paths) { + const auto unique_path_points = motion_utils::removeOverlapPoints(predicted_path.path); + if (unique_path_points.size() < 2) continue; + const auto time_step = rclcpp::Duration(predicted_path.time_step).seconds(); + const auto enter_point = + geometry_msgs::msg::Point().set__x(range.entering_point.x()).set__y(range.entering_point.y()); + const auto enter_segment_idx = + motion_utils::findNearestSegmentIndex(unique_path_points, enter_point); + const auto enter_offset = motion_utils::calcLongitudinalOffsetToSegment( + unique_path_points, enter_segment_idx, enter_point); + const auto enter_lat_dist = + std::abs(motion_utils::calcLateralOffset(unique_path_points, enter_point, enter_segment_idx)); + const auto enter_segment_length = tier4_autoware_utils::calcDistance2d( + unique_path_points[enter_segment_idx], unique_path_points[enter_segment_idx + 1]); + const auto enter_offset_ratio = enter_offset / enter_segment_length; + const auto enter_time = + static_cast(enter_segment_idx) * time_step + enter_offset_ratio * time_step; + + const auto exit_point = + geometry_msgs::msg::Point().set__x(range.exiting_point.x()).set__y(range.exiting_point.y()); + const auto exit_segment_idx = + motion_utils::findNearestSegmentIndex(unique_path_points, exit_point); + const auto exit_offset = motion_utils::calcLongitudinalOffsetToSegment( + unique_path_points, exit_segment_idx, exit_point); + const auto exit_lat_dist = + std::abs(motion_utils::calcLateralOffset(unique_path_points, exit_point, exit_segment_idx)); + const auto exit_segment_length = tier4_autoware_utils::calcDistance2d( + unique_path_points[exit_segment_idx], unique_path_points[exit_segment_idx + 1]); + const auto exit_offset_ratio = exit_offset / static_cast(exit_segment_length); + const auto exit_time = + static_cast(exit_segment_idx) * time_step + exit_offset_ratio * time_step; + + RCLCPP_DEBUG( + logger, "\t\t\tPredicted path (time step = %2.2fs): enter @ %2.2fs, exit @ %2.2fs", time_step, + enter_time, exit_time); + // predicted path is too far from the overlapping range to be relevant + const auto is_far_from_entering_point = enter_lat_dist > max_deviation; + const auto is_far_from_exiting_point = exit_lat_dist > max_deviation; + if (is_far_from_entering_point && is_far_from_exiting_point) { + RCLCPP_DEBUG( + logger, + " * far_from_enter (%d) = %2.2fm | far_from_exit (%d) = %2.2fm | max_dev = %2.2fm\n", + is_far_from_entering_point, enter_lat_dist, is_far_from_exiting_point, exit_lat_dist, + max_deviation); + continue; + } + const auto is_last_predicted_path_point = + (exit_segment_idx + 2 == unique_path_points.size() || + enter_segment_idx + 2 == unique_path_points.size()); + const auto does_not_reach_overlap = + is_last_predicted_path_point && (std::min(exit_offset, enter_offset) > max_lon_deviation); + if (does_not_reach_overlap) { + RCLCPP_DEBUG( + logger, " * does not reach the overlap = %2.2fm | max_dev = %2.2fm\n", + std::min(exit_offset, enter_offset), max_lon_deviation); + continue; + } + + const auto same_driving_direction_as_ego = enter_time < exit_time; + if (same_driving_direction_as_ego) { + worst_enter_time = worst_enter_time ? std::min(*worst_enter_time, enter_time) : enter_time; + worst_exit_time = worst_exit_time ? std::max(*worst_exit_time, exit_time) : exit_time; + } else { + worst_enter_time = worst_enter_time ? std::max(*worst_enter_time, enter_time) : enter_time; + worst_exit_time = worst_exit_time ? std::min(*worst_exit_time, exit_time) : exit_time; + } + } + if (worst_enter_time && worst_exit_time) { + RCLCPP_DEBUG( + logger, "\t\t\t * found enter/exit time [%2.2f, %2.2f]\n", *worst_enter_time, + *worst_exit_time); + return std::make_pair(*worst_enter_time, *worst_exit_time); + } + RCLCPP_DEBUG(logger, "\t\t\t * enter/exit time not found\n"); + return {}; +} + +std::optional> object_time_to_range( + const autoware_auto_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, + const DecisionInputs & inputs, const rclcpp::Logger & logger) +{ + const auto & p = object.kinematics.initial_pose_with_covariance.pose.position; + const auto object_point = lanelet::BasicPoint2d(p.x, p.y); + const auto half_size = object.shape.dimensions.x / 2.0; + lanelet::ConstLanelets object_lanelets; + for (const auto & ll : inputs.lanelets) + if (boost::geometry::within(object_point, ll.polygon2d().basicPolygon())) + object_lanelets.push_back(ll); + + geometry_msgs::msg::Pose pose; + pose.position.set__x(range.entering_point.x()).set__y(range.entering_point.y()); + const auto range_enter_length = lanelet::utils::getArcCoordinates({range.lane}, pose).length; + pose.position.set__x(range.exiting_point.x()).set__y(range.exiting_point.y()); + const auto range_exit_length = lanelet::utils::getArcCoordinates({range.lane}, pose).length; + const auto range_size = std::abs(range_enter_length - range_exit_length); + auto worst_enter_dist = std::optional(); + auto worst_exit_dist = std::optional(); + for (const auto & lane : object_lanelets) { + const auto path = inputs.route_handler->getRoutingGraphPtr()->shortestPath(lane, range.lane); + RCLCPP_DEBUG( + logger, "\t\t\tPath ? %d [from %ld to %ld]\n", path.has_value(), lane.id(), range.lane.id()); + if (path) { + lanelet::ConstLanelets lls; + for (const auto & ll : *path) lls.push_back(ll); + pose.position.set__x(object_point.x()).set__y(object_point.y()); + const auto object_curr_length = lanelet::utils::getArcCoordinates(lls, pose).length; + pose.position.set__x(range.entering_point.x()).set__y(range.entering_point.y()); + const auto enter_dist = + lanelet::utils::getArcCoordinates(lls, pose).length - object_curr_length; + pose.position.set__x(range.exiting_point.x()).set__y(range.exiting_point.y()); + const auto exit_dist = + lanelet::utils::getArcCoordinates(lls, pose).length - object_curr_length; + RCLCPP_DEBUG( + logger, "\t\t\t%2.2f -> [%2.2f(%2.2f, %2.2f) - %2.2f(%2.2f, %2.2f)]\n", object_curr_length, + enter_dist, range.entering_point.x(), range.entering_point.y(), exit_dist, + range.exiting_point.x(), range.exiting_point.y()); + const auto already_entered_range = std::abs(enter_dist - exit_dist) > range_size * 2.0; + if (already_entered_range) continue; + // multiple paths to the overlap -> be conservative and use the "worst" case + // "worst" = min/max arc length depending on if the lane is running opposite to the ego + // trajectory + const auto is_opposite = enter_dist > exit_dist; + if (!worst_enter_dist) + worst_enter_dist = enter_dist; + else if (is_opposite) + worst_enter_dist = std::max(*worst_enter_dist, enter_dist); + else + worst_enter_dist = std::min(*worst_enter_dist, enter_dist); + if (!worst_exit_dist) + worst_exit_dist = exit_dist; + else if (is_opposite) + worst_exit_dist = std::max(*worst_exit_dist, exit_dist); + else + worst_exit_dist = std::min(*worst_exit_dist, exit_dist); + } + } + if (worst_enter_dist && worst_exit_dist) { + const auto v = object.kinematics.initial_twist_with_covariance.twist.linear.x; + return std::make_pair((*worst_enter_dist - half_size) / v, (*worst_exit_dist + half_size) / v); + } + return {}; +} + +bool threshold_condition(const RangeTimes & range_times, const PlannerParam & params) +{ + const auto enter_within_threshold = + range_times.object.enter_time > 0.0 && range_times.object.enter_time < params.time_threshold; + const auto exit_within_threshold = + range_times.object.exit_time > 0.0 && range_times.object.exit_time < params.time_threshold; + return enter_within_threshold || exit_within_threshold; +} + +bool intervals_condition( + const RangeTimes & range_times, const PlannerParam & params, const rclcpp::Logger & logger) +{ + const auto opposite_way_condition = [&]() -> bool { + const auto ego_exits_before_object_enters = + range_times.ego.exit_time + params.intervals_ego_buffer < + range_times.object.enter_time + params.intervals_obj_buffer; + RCLCPP_DEBUG( + logger, + "\t\t\t[Intervals] (opposite way) ego exit %2.2fs < obj enter %2.2fs ? -> should not " + "enter = %d\n", + range_times.ego.exit_time + params.intervals_ego_buffer, + range_times.object.enter_time + params.intervals_obj_buffer, ego_exits_before_object_enters); + return ego_exits_before_object_enters; + }; + const auto same_way_condition = [&]() -> bool { + const auto object_enters_during_overlap = + range_times.ego.enter_time - params.intervals_ego_buffer < + range_times.object.enter_time + params.intervals_obj_buffer && + range_times.object.enter_time - params.intervals_obj_buffer - range_times.ego.exit_time < + range_times.ego.exit_time + params.intervals_ego_buffer; + const auto object_exits_during_overlap = + range_times.ego.enter_time - params.intervals_ego_buffer < + range_times.object.exit_time + params.intervals_obj_buffer && + range_times.object.exit_time - params.intervals_obj_buffer - range_times.ego.exit_time < + range_times.ego.exit_time + params.intervals_ego_buffer; + RCLCPP_DEBUG( + logger, + "\t\t\t[Intervals] obj enters during overlap ? %d OR obj exits during overlap %d ? -> should " + "not " + "enter = %d\n", + object_enters_during_overlap, object_exits_during_overlap, + object_enters_during_overlap || object_exits_during_overlap); + return object_enters_during_overlap || object_exits_during_overlap; + }; + + const auto object_is_going_same_way = + range_times.object.enter_time < range_times.object.exit_time; + return (object_is_going_same_way && same_way_condition()) || + (!object_is_going_same_way && opposite_way_condition()); +} + +bool ttc_condition( + const RangeTimes & range_times, const PlannerParam & params, const rclcpp::Logger & logger) +{ + const auto ttc_at_enter = range_times.ego.enter_time - range_times.object.enter_time; + const auto ttc_at_exit = range_times.ego.exit_time - range_times.object.exit_time; + const auto collision_during_overlap = (ttc_at_enter < 0.0) != (ttc_at_exit < 0.0); + const auto ttc_is_bellow_threshold = + std::min(std::abs(ttc_at_enter), std::abs(ttc_at_exit)) <= params.ttc_threshold; + RCLCPP_DEBUG( + logger, "\t\t\t[TTC] (%2.2fs - %2.2fs) -> %d\n", ttc_at_enter, ttc_at_exit, + (collision_during_overlap || ttc_is_bellow_threshold)); + return collision_during_overlap || ttc_is_bellow_threshold; +} + +bool will_collide_on_range( + const RangeTimes & range_times, const PlannerParam & params, const rclcpp::Logger & logger) +{ + RCLCPP_DEBUG( + logger, " enter at %2.2fs, exits at %2.2fs\n", range_times.object.enter_time, + range_times.object.exit_time); + return (params.mode == "threshold" && threshold_condition(range_times, params)) || + (params.mode == "intervals" && intervals_condition(range_times, params, logger)) || + (params.mode == "ttc" && ttc_condition(range_times, params, logger)); +} + +bool should_not_enter( + const OverlapRange & range, const DecisionInputs & inputs, const PlannerParam & params, + const rclcpp::Logger & logger) +{ + RangeTimes range_times{}; + range_times.ego.enter_time = + time_along_trajectory(inputs.ego_data, range.entering_trajectory_idx, params.ego_min_velocity); + range_times.ego.exit_time = + time_along_trajectory(inputs.ego_data, range.exiting_trajectory_idx, params.ego_min_velocity); + RCLCPP_DEBUG( + logger, "\t[%lu -> %lu] %ld | ego enters at %2.2f, exits at %2.2f\n", + range.entering_trajectory_idx, range.exiting_trajectory_idx, range.lane.id(), + range_times.ego.enter_time, range_times.ego.exit_time); + for (const auto & object : inputs.objects.objects) { + RCLCPP_DEBUG( + logger, "\t\t[%s] going at %2.2fm/s", + tier4_autoware_utils::toHexString(object.object_id).c_str(), + object.kinematics.initial_twist_with_covariance.twist.linear.x); + if (object.kinematics.initial_twist_with_covariance.twist.linear.x < params.objects_min_vel) { + RCLCPP_DEBUG(logger, " SKIP (velocity bellow threshold %2.2fm/s)\n", params.objects_min_vel); + continue; // skip objects with velocity bellow a threshold + } + // skip objects that are already on the interval + const auto enter_exit_time = + params.objects_use_predicted_paths + ? object_time_to_range( + object, range, inputs.route_handler, params.objects_dist_buffer, logger) + : object_time_to_range(object, range, inputs, logger); + if (!enter_exit_time) { + RCLCPP_DEBUG(logger, " SKIP (no enter/exit times found)\n"); + continue; // skip objects that are not driving towards the overlapping range + } + + range_times.object.enter_time = enter_exit_time->first; + range_times.object.exit_time = enter_exit_time->second; + if (will_collide_on_range(range_times, params, logger)) { + range.debug.times = range_times; + range.debug.object = object; + return true; + } + } + range.debug.times = range_times; + return false; +} + +void set_decision_velocity( + std::optional & decision, const double distance, const PlannerParam & params) +{ + if (distance < params.stop_dist_threshold) { + decision->velocity = 0.0; + } else if (distance < params.slow_dist_threshold) { + decision->velocity = params.slow_velocity; + } else { + decision.reset(); + } +} + +std::optional calculate_decision( + const OverlapRange & range, const DecisionInputs & inputs, const PlannerParam & params, + const rclcpp::Logger & logger) +{ + std::optional decision; + if (should_not_enter(range, inputs, params, logger)) { + decision.emplace(); + decision->target_trajectory_idx = inputs.ego_data.first_trajectory_idx + + range.entering_trajectory_idx; // add offset from curr pose + decision->lane_to_avoid = range.lane; + const auto ego_dist_to_range = + distance_along_trajectory(inputs.ego_data, range.entering_trajectory_idx); + set_decision_velocity(decision, ego_dist_to_range, params); + } + return decision; +} + +std::vector calculate_decisions( + const DecisionInputs & inputs, const PlannerParam & params, const rclcpp::Logger & logger) +{ + std::vector decisions; + for (const auto & range : inputs.ranges) { + if (range.entering_trajectory_idx == 0UL) continue; // skip if we already entered the range + const auto optional_decision = calculate_decision(range, inputs, params, logger); + range.debug.decision = optional_decision; + if (optional_decision) decisions.push_back(*optional_decision); + } + return decisions; +} + +} // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.hpp new file mode 100644 index 0000000000000..2aa3a8b490bf6 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.hpp @@ -0,0 +1,116 @@ +// 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 DECISIONS_HPP_ +#define DECISIONS_HPP_ + +#include "types.hpp" + +#include +#include + +#include + +#include + +#include +#include +#include +#include + +namespace autoware::motion_velocity_planner::out_of_lane +{ +/// @brief calculate the distance along the ego trajectory between ego and some target trajectory +/// index +/// @param [in] ego_data data related to the ego vehicle +/// @param [in] target_idx target ego trajectory index +/// @return distance between ego and the target [m] +double distance_along_trajectory(const EgoData & ego_data, const size_t target_idx); +/// @brief estimate the time when ego will reach some target trajectory index +/// @param [in] ego_data data related to the ego vehicle +/// @param [in] target_idx target ego trajectory index +/// @param [in] min_velocity minimum ego velocity used to estimate the time +/// @return time taken by ego to reach the target [s] +double time_along_trajectory(const EgoData & ego_data, const size_t target_idx); +/// @brief use an object's predicted paths to estimate the times it will reach the enter and exit +/// points of an overlapping range +/// @details times when the predicted paths of the object enters/exits the range are calculated +/// but may not exist (e.g,, predicted path ends before reaching the end of the range) +/// @param [in] object dynamic object +/// @param [in] range overlapping range +/// @param [in] route_handler route handler used to estimate the path of the dynamic object +/// @param [in] logger ros logger +/// @return an optional pair (time at enter [s], time at exit [s]). If the dynamic object drives in +/// the opposite direction, time at enter > time at exit +std::optional> object_time_to_range( + const autoware_auto_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, + const std::shared_ptr route_handler, const double dist_buffer, + const rclcpp::Logger & logger); +/// @brief use the lanelet map to estimate the times when an object will reach the enter and exit +/// points of an overlapping range +/// @param [in] object dynamic object +/// @param [in] range overlapping range +/// @param [in] inputs information used to take decisions (ranges, ego and objects data, route +/// handler, lanelets) +/// @param [in] dist_buffer extra distance used to estimate if a collision will occur on the range +/// @param [in] logger ros logger +/// @return an optional pair (time at enter [s], time at exit [s]). If the dynamic object drives in +/// the opposite direction, time at enter > time at exit. +std::optional> object_time_to_range( + const autoware_auto_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, + const DecisionInputs & inputs, const rclcpp::Logger & logger); +/// @brief decide whether an object is coming in the range at the same time as ego +/// @details the condition depends on the mode (threshold, intervals, ttc) +/// @param [in] range_times times when ego and the object enter/exit the range +/// @param [in] params parameters +/// @param [in] logger ros logger +bool will_collide_on_range( + const RangeTimes & range_times, const PlannerParam & params, const rclcpp::Logger & logger); +/// @brief check whether we should avoid entering the given range +/// @param [in] range the range to check +/// @param [in] inputs information used to take decisions (ranges, ego and objects data, route +/// handler, lanelets) +/// @param [in] params parameters +/// @param [in] logger ros logger +/// @return return true if we should avoid entering the range +bool should_not_enter( + const OverlapRange & range, const DecisionInputs & inputs, const PlannerParam & params, + const rclcpp::Logger & logger); +/// @brief set the velocity of a decision (or unset it) based on the distance away from the range +/// @param [out] decision decision to update (either set its velocity or unset the decision) +/// @param [in] distance distance between ego and the range corresponding to the decision +/// @param [in] params parameters +void set_decision_velocity( + std::optional & decision, const double distance, const PlannerParam & params); +/// @brief calculate the decision to slowdown or stop before an overlapping range +/// @param [in] range the range to check +/// @param [in] inputs information used to take decisions (ranges, ego and objects data, route +/// handler, lanelets) +/// @param [in] params parameters +/// @param [in] logger ros logger +/// @return return an optional decision to slowdown or stop +std::optional calculate_decision( + const OverlapRange & range, const DecisionInputs & inputs, const PlannerParam & params, + const rclcpp::Logger & logger); +/// @brief calculate decisions to slowdown or stop before some overlapping ranges +/// @param [in] inputs information used to take decisions (ranges, ego and objects data, route +/// handler, lanelets) +/// @param [in] params parameters +/// @param [in] logger ros logger +/// @return return the calculated decisions to slowdown or stop +std::vector calculate_decisions( + const DecisionInputs & inputs, const PlannerParam & params, const rclcpp::Logger & logger); +} // namespace autoware::motion_velocity_planner::out_of_lane + +#endif // DECISIONS_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp new file mode 100644 index 0000000000000..31631fb577b09 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp @@ -0,0 +1,150 @@ +// 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 "filter_predicted_objects.hpp" + +#include +#include + +#include + +#include +#include + +#include + +namespace autoware::motion_velocity_planner::out_of_lane +{ +void cut_predicted_path_beyond_line( + autoware_auto_perception_msgs::msg::PredictedPath & predicted_path, + const lanelet::BasicLineString2d & stop_line, const double object_front_overhang) +{ + if (predicted_path.path.empty() || stop_line.size() < 2) return; + + auto stop_line_idx = 0UL; + bool found = false; + lanelet::BasicSegment2d path_segment; + path_segment.first.x() = predicted_path.path.front().position.x; + path_segment.first.y() = predicted_path.path.front().position.y; + for (stop_line_idx = 1; stop_line_idx < predicted_path.path.size(); ++stop_line_idx) { + path_segment.second.x() = predicted_path.path[stop_line_idx].position.x; + path_segment.second.y() = predicted_path.path[stop_line_idx].position.y; + if (boost::geometry::intersects(stop_line, path_segment)) { + found = true; + break; + } + path_segment.first = path_segment.second; + } + if (found) { + auto cut_idx = stop_line_idx; + double arc_length = 0; + while (cut_idx > 0 && arc_length < object_front_overhang) { + arc_length += tier4_autoware_utils::calcDistance2d( + predicted_path.path[cut_idx], predicted_path.path[cut_idx - 1]); + --cut_idx; + } + predicted_path.path.resize(cut_idx); + } +} + +std::optional find_next_stop_line( + const autoware_auto_perception_msgs::msg::PredictedPath & path, + const std::shared_ptr planner_data) +{ + lanelet::ConstLanelets lanelets; + lanelet::BasicLineString2d query_line; + for (const auto & p : path.path) query_line.emplace_back(p.position.x, p.position.y); + const auto query_results = lanelet::geometry::findWithin2d( + planner_data->route_handler->getLaneletMapPtr()->laneletLayer, query_line); + for (const auto & r : query_results) lanelets.push_back(r.second); + for (const auto & ll : lanelets) { + for (const auto & element : ll.regulatoryElementsAs()) { + const auto traffic_signal_stamped = planner_data->get_traffic_signal(element->id()); + if ( + traffic_signal_stamped.has_value() && element->stopLine().has_value() && + traffic_light_utils::isTrafficSignalStop(ll, traffic_signal_stamped.value().signal)) { + lanelet::BasicLineString2d stop_line; + for (const auto & p : *(element->stopLine())) stop_line.emplace_back(p.x(), p.y()); + return stop_line; + } + } + } + return std::nullopt; +} + +void cut_predicted_path_beyond_red_lights( + autoware_auto_perception_msgs::msg::PredictedPath & predicted_path, + const std::shared_ptr planner_data, const double object_front_overhang) +{ + const auto stop_line = find_next_stop_line(predicted_path, planner_data); + if (stop_line) { + // we use a longer stop line to also cut predicted paths that slightly go around the stop line + auto longer_stop_line = *stop_line; + const auto diff = stop_line->back() - stop_line->front(); + longer_stop_line.front() -= diff * 0.5; + longer_stop_line.back() += diff * 0.5; + cut_predicted_path_beyond_line(predicted_path, longer_stop_line, object_front_overhang); + } +} + +autoware_auto_perception_msgs::msg::PredictedObjects filter_predicted_objects( + const std::shared_ptr planner_data, const EgoData & ego_data, + const PlannerParam & params) +{ + autoware_auto_perception_msgs::msg::PredictedObjects filtered_objects; + filtered_objects.header = planner_data->predicted_objects->header; + for (const auto & object : planner_data->predicted_objects->objects) { + const auto is_pedestrian = + std::find_if(object.classification.begin(), object.classification.end(), [](const auto & c) { + return c.label == autoware_auto_perception_msgs::msg::ObjectClassification::PEDESTRIAN; + }) != object.classification.end(); + if (is_pedestrian) continue; + + auto filtered_object = object; + const auto is_invalid_predicted_path = [&](const auto & predicted_path) { + const auto is_low_confidence = predicted_path.confidence < params.objects_min_confidence; + const auto no_overlap_path = motion_utils::removeOverlapPoints(predicted_path.path); + if (no_overlap_path.size() <= 1) return true; + const auto lat_offset_to_current_ego = + std::abs(motion_utils::calcLateralOffset(no_overlap_path, ego_data.pose.position)); + const auto is_crossing_ego = + lat_offset_to_current_ego <= + object.shape.dimensions.y / 2.0 + std::max( + params.left_offset + params.extra_left_offset, + params.right_offset + params.extra_right_offset); + return is_low_confidence || is_crossing_ego; + }; + if (params.objects_use_predicted_paths) { + auto & predicted_paths = filtered_object.kinematics.predicted_paths; + const auto new_end = + std::remove_if(predicted_paths.begin(), predicted_paths.end(), is_invalid_predicted_path); + predicted_paths.erase(new_end, predicted_paths.end()); + if (params.objects_cut_predicted_paths_beyond_red_lights) + for (auto & predicted_path : predicted_paths) + cut_predicted_path_beyond_red_lights( + predicted_path, planner_data, filtered_object.shape.dimensions.x); + predicted_paths.erase( + std::remove_if( + predicted_paths.begin(), predicted_paths.end(), + [](const auto & p) { return p.path.empty(); }), + predicted_paths.end()); + } + + if (!params.objects_use_predicted_paths || !filtered_object.kinematics.predicted_paths.empty()) + filtered_objects.objects.push_back(filtered_object); + } + return filtered_objects; +} + +} // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.hpp new file mode 100644 index 0000000000000..0770fbc0dcff1 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.hpp @@ -0,0 +1,60 @@ +// Copyright 2024-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 FILTER_PREDICTED_OBJECTS_HPP_ +#define FILTER_PREDICTED_OBJECTS_HPP_ + +#include "types.hpp" + +#include + +#include +#include + +namespace autoware::motion_velocity_planner::out_of_lane +{ +/// @brief cut a predicted path beyond the given stop line +/// @param [inout] predicted_path predicted path to cut +/// @param [in] stop_line stop line used for cutting +/// @param [in] object_front_overhang extra distance to cut ahead of the stop line +void cut_predicted_path_beyond_line( + autoware_auto_perception_msgs::msg::PredictedPath & predicted_path, + const lanelet::BasicLineString2d & stop_line, const double object_front_overhang); + +/// @brief find the next red light stop line along the given path +/// @param [in] path predicted path to check for a stop line +/// @param [in] planner_data planner data with stop line information +/// @return the first red light stop line found along the path (if any) +std::optional find_next_stop_line( + const autoware_auto_perception_msgs::msg::PredictedPath & path, + const std::shared_ptr planner_data); + +/// @brief cut predicted path beyond stop lines of red lights +/// @param [inout] predicted_path predicted path to cut +/// @param [in] planner_data planner data to get the map and traffic light information +void cut_predicted_path_beyond_red_lights( + autoware_auto_perception_msgs::msg::PredictedPath & predicted_path, + const std::shared_ptr planner_data, const double object_front_overhang); + +/// @brief filter predicted objects and their predicted paths +/// @param [in] planner_data planner data +/// @param [in] ego_data ego data +/// @param [in] params parameters +/// @return filtered predicted objects +autoware_auto_perception_msgs::msg::PredictedObjects filter_predicted_objects( + const std::shared_ptr planner_data, const EgoData & ego_data, + const PlannerParam & params); +} // namespace autoware::motion_velocity_planner::out_of_lane + +#endif // FILTER_PREDICTED_OBJECTS_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.cpp new file mode 100644 index 0000000000000..824a847b17414 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.cpp @@ -0,0 +1,93 @@ +// 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 "footprint.hpp" + +#include + +#include + +#include +#include + +#include +#include + +namespace autoware::motion_velocity_planner::out_of_lane +{ +tier4_autoware_utils::Polygon2d make_base_footprint( + const PlannerParam & p, const bool ignore_offset) +{ + tier4_autoware_utils::Polygon2d base_footprint; + const auto front_offset = ignore_offset ? 0.0 : p.extra_front_offset; + const auto rear_offset = ignore_offset ? 0.0 : p.extra_rear_offset; + const auto right_offset = ignore_offset ? 0.0 : p.extra_right_offset; + const auto left_offset = ignore_offset ? 0.0 : p.extra_left_offset; + base_footprint.outer() = { + {p.front_offset + front_offset, p.left_offset + left_offset}, + {p.front_offset + front_offset, p.right_offset - right_offset}, + {p.rear_offset - rear_offset, p.right_offset - right_offset}, + {p.rear_offset - rear_offset, p.left_offset + left_offset}}; + return base_footprint; +} + +lanelet::BasicPolygon2d project_to_pose( + const tier4_autoware_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose) +{ + const auto angle = tf2::getYaw(pose.orientation); + const auto rotated_footprint = tier4_autoware_utils::rotatePolygon(base_footprint, angle); + lanelet::BasicPolygon2d footprint; + for (const auto & p : rotated_footprint.outer()) + footprint.emplace_back(p.x() + pose.position.x, p.y() + pose.position.y); + return footprint; +} + +std::vector calculate_trajectory_footprints( + const EgoData & ego_data, const PlannerParam & params) +{ + const auto base_footprint = make_base_footprint(params); + std::vector trajectory_footprints; + trajectory_footprints.reserve(ego_data.trajectory_points.size()); + double length = 0.0; + const auto range = std::max(params.slow_dist_threshold, params.stop_dist_threshold) + + params.front_offset + params.extra_front_offset; + for (auto i = ego_data.first_trajectory_idx; + i < ego_data.trajectory_points.size() && length < range; ++i) { + const auto & trajectory_pose = ego_data.trajectory_points[i].pose; + const auto angle = tf2::getYaw(trajectory_pose.orientation); + const auto rotated_footprint = tier4_autoware_utils::rotatePolygon(base_footprint, angle); + lanelet::BasicPolygon2d footprint; + for (const auto & p : rotated_footprint.outer()) + footprint.emplace_back( + p.x() + trajectory_pose.position.x, p.y() + trajectory_pose.position.y); + trajectory_footprints.push_back(footprint); + if (i + 1 < ego_data.trajectory_points.size()) + length += tier4_autoware_utils::calcDistance2d( + trajectory_pose, ego_data.trajectory_points[i + 1].pose); + } + return trajectory_footprints; +} + +lanelet::BasicPolygon2d calculate_current_ego_footprint( + const EgoData & ego_data, const PlannerParam & params, const bool ignore_offset) +{ + const auto base_footprint = make_base_footprint(params, ignore_offset); + const auto angle = tf2::getYaw(ego_data.pose.orientation); + const auto rotated_footprint = tier4_autoware_utils::rotatePolygon(base_footprint, angle); + lanelet::BasicPolygon2d footprint; + for (const auto & p : rotated_footprint.outer()) + footprint.emplace_back(p.x() + ego_data.pose.position.x, p.y() + ego_data.pose.position.y); + return footprint; +} +} // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.hpp new file mode 100644 index 0000000000000..7b80dd9618bb7 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/footprint.hpp @@ -0,0 +1,59 @@ +// 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 FOOTPRINT_HPP_ +#define FOOTPRINT_HPP_ + +#include "types.hpp" + +#include + +#include + +namespace autoware::motion_velocity_planner +{ +namespace out_of_lane +{ +/// @brief create the base footprint of ego +/// @param [in] p parameters used to create the footprint +/// @param [in] ignore_offset optional parameter, if true, ignore the "extra offsets" to build the +/// footprint +/// @return base ego footprint +tier4_autoware_utils::Polygon2d make_base_footprint( + const PlannerParam & p, const bool ignore_offset = false); +/// @brief project a footprint to the given pose +/// @param [in] base_footprint footprint to project +/// @param [in] pose projection pose +/// @return footprint projected to the given pose +lanelet::BasicPolygon2d project_to_pose( + const tier4_autoware_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose); +/// @brief calculate the trajectory footprints +/// @details the resulting polygon follows the format used by the lanelet library: clockwise order +/// and implicit closing edge +/// @param [in] ego_data data related to the ego vehicle (includes its trajectory) +/// @param [in] params parameters +/// @return polygon footprints for each trajectory point starting from ego's current position +std::vector calculate_trajectory_footprints( + const EgoData & ego_data, const PlannerParam & params); +/// @brief calculate the current ego footprint +/// @param [in] ego_data data related to the ego vehicle +/// @param [in] params parameters +/// @param [in] ignore_offset optional parameter, if true, ignore the "extra offsets" to build the +/// footprint +lanelet::BasicPolygon2d calculate_current_ego_footprint( + const EgoData & ego_data, const PlannerParam & params, const bool ignore_offset = false); +} // namespace out_of_lane +} // namespace autoware::motion_velocity_planner + +#endif // FOOTPRINT_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.cpp new file mode 100644 index 0000000000000..23dbf77f08151 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.cpp @@ -0,0 +1,126 @@ +// 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 "lanelets_selection.hpp" + +#include + +#include +#include + +#include +#include + +namespace autoware::motion_velocity_planner::out_of_lane +{ + +lanelet::ConstLanelets consecutive_lanelets( + const std::shared_ptr route_handler, + const lanelet::ConstLanelet & lanelet) +{ + lanelet::ConstLanelets consecutives = route_handler->getRoutingGraphPtr()->following(lanelet); + const auto previous = route_handler->getRoutingGraphPtr()->previous(lanelet); + consecutives.insert(consecutives.end(), previous.begin(), previous.end()); + return consecutives; +} + +lanelet::ConstLanelets get_missing_lane_change_lanelets( + lanelet::ConstLanelets & trajectory_lanelets, + const std::shared_ptr route_handler) +{ + lanelet::ConstLanelets missing_lane_change_lanelets; + const auto & routing_graph = *route_handler->getRoutingGraphPtr(); + lanelet::ConstLanelets adjacents; + lanelet::ConstLanelets consecutives; + for (const auto & ll : trajectory_lanelets) { + const auto consecutives_of_ll = consecutive_lanelets(route_handler, ll); + std::copy_if( + consecutives_of_ll.begin(), consecutives_of_ll.end(), std::back_inserter(consecutives), + [&](const auto & l) { return !contains_lanelet(consecutives, l.id()); }); + const auto adjacents_of_ll = routing_graph.besides(ll); + std::copy_if( + adjacents_of_ll.begin(), adjacents_of_ll.end(), std::back_inserter(adjacents), + [&](const auto & l) { return !contains_lanelet(adjacents, l.id()); }); + } + std::copy_if( + adjacents.begin(), adjacents.end(), std::back_inserter(missing_lane_change_lanelets), + [&](const auto & l) { + return !contains_lanelet(missing_lane_change_lanelets, l.id()) && + !contains_lanelet(trajectory_lanelets, l.id()) && + contains_lanelet(consecutives, l.id()); + }); + return missing_lane_change_lanelets; +} + +lanelet::ConstLanelets calculate_trajectory_lanelets( + const EgoData & ego_data, const std::shared_ptr route_handler) +{ + const auto lanelet_map_ptr = route_handler->getLaneletMapPtr(); + lanelet::ConstLanelets trajectory_lanelets; + lanelet::BasicLineString2d trajectory_ls; + for (const auto & p : ego_data.trajectory_points) + trajectory_ls.emplace_back(p.pose.position.x, p.pose.position.y); + for (const auto & dist_lanelet : + lanelet::geometry::findWithin2d(lanelet_map_ptr->laneletLayer, trajectory_ls)) { + if (!contains_lanelet(trajectory_lanelets, dist_lanelet.second.id())) + trajectory_lanelets.push_back(dist_lanelet.second); + } + const auto missing_lanelets = + get_missing_lane_change_lanelets(trajectory_lanelets, route_handler); + trajectory_lanelets.insert( + trajectory_lanelets.end(), missing_lanelets.begin(), missing_lanelets.end()); + return trajectory_lanelets; +} + +lanelet::ConstLanelets calculate_ignored_lanelets( + const EgoData & ego_data, const lanelet::ConstLanelets & trajectory_lanelets, + const std::shared_ptr route_handler, + const PlannerParam & params) +{ + lanelet::ConstLanelets ignored_lanelets; + // ignore lanelets directly behind ego + const auto behind = + tier4_autoware_utils::calcOffsetPose(ego_data.pose, params.rear_offset, 0.0, 0.0); + const lanelet::BasicPoint2d behind_point(behind.position.x, behind.position.y); + const auto behind_lanelets = lanelet::geometry::findWithin2d( + route_handler->getLaneletMapPtr()->laneletLayer, behind_point, 0.0); + for (const auto & l : behind_lanelets) { + const auto is_trajectory_lanelet = contains_lanelet(trajectory_lanelets, l.second.id()); + if (!is_trajectory_lanelet) ignored_lanelets.push_back(l.second); + } + return ignored_lanelets; +} + +lanelet::ConstLanelets calculate_other_lanelets( + const EgoData & ego_data, const lanelet::ConstLanelets & trajectory_lanelets, + const lanelet::ConstLanelets & ignored_lanelets, + const std::shared_ptr route_handler, + const PlannerParam & params) +{ + lanelet::ConstLanelets other_lanelets; + const lanelet::BasicPoint2d ego_point(ego_data.pose.position.x, ego_data.pose.position.y); + const auto lanelets_within_range = lanelet::geometry::findWithin2d( + route_handler->getLaneletMapPtr()->laneletLayer, ego_point, + std::max(params.slow_dist_threshold, params.stop_dist_threshold) + params.front_offset + + params.extra_front_offset); + for (const auto & ll : lanelets_within_range) { + if (std::string(ll.second.attributeOr(lanelet::AttributeName::Subtype, "none")) != "road") + continue; + const auto is_trajectory_lanelet = contains_lanelet(trajectory_lanelets, ll.second.id()); + const auto is_ignored_lanelet = contains_lanelet(ignored_lanelets, ll.second.id()); + if (!is_trajectory_lanelet && !is_ignored_lanelet) other_lanelets.push_back(ll.second); + } + return other_lanelets; +} +} // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.hpp new file mode 100644 index 0000000000000..c7351f0a98e89 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/lanelets_selection.hpp @@ -0,0 +1,80 @@ +// 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 LANELETS_SELECTION_HPP_ +#define LANELETS_SELECTION_HPP_ + +#include "types.hpp" + +#include + +#include + +#include + +namespace autoware::motion_velocity_planner::out_of_lane +{ +/// @brief checks if a lanelet is already contained in a vector of lanelets +/// @param [in] lanelets vector to check +/// @param [in] id lanelet id to check +/// @return true if the given vector contains a lanelet of the given id +inline bool contains_lanelet(const lanelet::ConstLanelets & lanelets, const lanelet::Id id) +{ + return std::find_if(lanelets.begin(), lanelets.end(), [&](const auto & l) { + return l.id() == id; + }) != lanelets.end(); +}; + +/// @brief calculate lanelets crossed by the ego trajectory +/// @details calculated from the ids of the trajectory msg, the lanelets containing trajectory +/// points +/// @param [in] ego_data data about the ego vehicle +/// @param [in] route_handler route handler +/// @return lanelets crossed by the ego vehicle +lanelet::ConstLanelets calculate_trajectory_lanelets( + const EgoData & ego_data, const std::shared_ptr route_handler); +/// @brief calculate lanelets that may not be crossed by the trajectory but may be overlapped during +/// a lane change +/// @param [in] trajectory_lanelets lanelets driven by the ego vehicle +/// @param [in] route_handler route handler +/// @return lanelets that may be overlapped by a lane change (and are not already in +/// trajectory_lanelets) +lanelet::ConstLanelets get_missing_lane_change_lanelets( + lanelet::ConstLanelets & trajectory_lanelets, + const std::shared_ptr route_handler); +/// @brief calculate lanelets that should be ignored +/// @param [in] ego_data data about the ego vehicle +/// @param [in] trajectory_lanelets lanelets driven by the ego vehicle +/// @param [in] route_handler route handler +/// @param [in] params parameters +/// @return lanelets to ignore +lanelet::ConstLanelets calculate_ignored_lanelets( + const EgoData & ego_data, const lanelet::ConstLanelets & trajectory_lanelets, + const std::shared_ptr route_handler, + const PlannerParam & params); +/// @brief calculate lanelets that should be checked by the module +/// @param [in] ego_data data about the ego vehicle +/// @param [in] trajectory_lanelets lanelets driven by the ego vehicle +/// @param [in] ignored_lanelets lanelets to ignore +/// @param [in] route_handler route handler +/// @param [in] params parameters +/// @return lanelets to check for overlaps +lanelet::ConstLanelets calculate_other_lanelets( + const EgoData & ego_data, const lanelet::ConstLanelets & trajectory_lanelets, + const lanelet::ConstLanelets & ignored_lanelets, + const std::shared_ptr route_handler, + const PlannerParam & params); +} // namespace autoware::motion_velocity_planner::out_of_lane + +#endif // LANELETS_SELECTION_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp new file mode 100644 index 0000000000000..b662186049342 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp @@ -0,0 +1,305 @@ +// 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 "out_of_lane_module.hpp" + +#include "calculate_slowdown_points.hpp" +#include "debug.hpp" +#include "decisions.hpp" +#include "filter_predicted_objects.hpp" +#include "footprint.hpp" +#include "lanelets_selection.hpp" +#include "overlapping_range.hpp" +#include "types.hpp" + +#include +#include +#include +#include +#include + +#include + +#include + +#include +#include +#include +#include + +namespace autoware::motion_velocity_planner +{ + +using visualization_msgs::msg::Marker; +using visualization_msgs::msg::MarkerArray; + +void OutOfLaneModule::init(rclcpp::Node & node, const std::string & module_name) +{ + module_name_ = module_name; + logger_ = node.get_logger(); + clock_ = node.get_clock(); + init_parameters(node); + velocity_factor_interface_.init(motion_utils::PlanningBehavior::ROUTE_OBSTACLE); + + debug_publisher_ = + node.create_publisher("~/" + ns_ + "/debug_markers", 1); + virtual_wall_publisher_ = + node.create_publisher("~/" + ns_ + "/virtual_walls", 1); +} +void OutOfLaneModule::init_parameters(rclcpp::Node & node) +{ + using tier4_autoware_utils::getOrDeclareParameter; + auto & pp = params_; + + pp.mode = getOrDeclareParameter(node, ns_ + ".mode"); + pp.skip_if_already_overlapping = + getOrDeclareParameter(node, ns_ + ".skip_if_already_overlapping"); + + pp.time_threshold = getOrDeclareParameter(node, ns_ + ".threshold.time_threshold"); + pp.intervals_ego_buffer = getOrDeclareParameter(node, ns_ + ".intervals.ego_time_buffer"); + pp.intervals_obj_buffer = + getOrDeclareParameter(node, ns_ + ".intervals.objects_time_buffer"); + pp.ttc_threshold = getOrDeclareParameter(node, ns_ + ".ttc.threshold"); + + pp.objects_min_vel = getOrDeclareParameter(node, ns_ + ".objects.minimum_velocity"); + pp.objects_use_predicted_paths = + getOrDeclareParameter(node, ns_ + ".objects.use_predicted_paths"); + pp.objects_min_confidence = + getOrDeclareParameter(node, ns_ + ".objects.predicted_path_min_confidence"); + pp.objects_dist_buffer = getOrDeclareParameter(node, ns_ + ".objects.distance_buffer"); + pp.objects_cut_predicted_paths_beyond_red_lights = + getOrDeclareParameter(node, ns_ + ".objects.cut_predicted_paths_beyond_red_lights"); + + pp.overlap_min_dist = getOrDeclareParameter(node, ns_ + ".overlap.minimum_distance"); + pp.overlap_extra_length = getOrDeclareParameter(node, ns_ + ".overlap.extra_length"); + + pp.skip_if_over_max_decel = + getOrDeclareParameter(node, ns_ + ".action.skip_if_over_max_decel"); + pp.precision = getOrDeclareParameter(node, ns_ + ".action.precision"); + pp.min_decision_duration = getOrDeclareParameter(node, ns_ + ".action.min_duration"); + pp.dist_buffer = getOrDeclareParameter(node, ns_ + ".action.distance_buffer"); + pp.slow_velocity = getOrDeclareParameter(node, ns_ + ".action.slowdown.velocity"); + pp.slow_dist_threshold = + getOrDeclareParameter(node, ns_ + ".action.slowdown.distance_threshold"); + pp.stop_dist_threshold = + getOrDeclareParameter(node, ns_ + ".action.stop.distance_threshold"); + + pp.ego_min_velocity = getOrDeclareParameter(node, ns_ + ".ego.min_assumed_velocity"); + pp.extra_front_offset = getOrDeclareParameter(node, ns_ + ".ego.extra_front_offset"); + pp.extra_rear_offset = getOrDeclareParameter(node, ns_ + ".ego.extra_rear_offset"); + pp.extra_left_offset = getOrDeclareParameter(node, ns_ + ".ego.extra_left_offset"); + pp.extra_right_offset = getOrDeclareParameter(node, ns_ + ".ego.extra_right_offset"); + const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo(); + pp.front_offset = vehicle_info.max_longitudinal_offset_m; + pp.rear_offset = vehicle_info.min_longitudinal_offset_m; + pp.left_offset = vehicle_info.max_lateral_offset_m; + pp.right_offset = vehicle_info.min_lateral_offset_m; +} + +void OutOfLaneModule::update_parameters(const std::vector & parameters) +{ + using tier4_autoware_utils::updateParam; + auto & pp = params_; + updateParam(parameters, ns_ + ".mode", pp.mode); + updateParam(parameters, ns_ + ".skip_if_already_overlapping", pp.skip_if_already_overlapping); + + updateParam(parameters, ns_ + ".threshold.time_threshold", pp.time_threshold); + updateParam(parameters, ns_ + ".intervals.ego_time_buffer", pp.intervals_ego_buffer); + updateParam(parameters, ns_ + ".intervals.objects_time_buffer", pp.intervals_obj_buffer); + updateParam(parameters, ns_ + ".ttc.threshold", pp.ttc_threshold); + + updateParam(parameters, ns_ + ".objects.minimum_velocity", pp.objects_min_vel); + updateParam(parameters, ns_ + ".objects.use_predicted_paths", pp.objects_use_predicted_paths); + updateParam( + parameters, ns_ + ".objects.predicted_path_min_confidence", pp.objects_min_confidence); + updateParam(parameters, ns_ + ".objects.distance_buffer", pp.objects_dist_buffer); + updateParam( + parameters, ns_ + ".objects.cut_predicted_paths_beyond_red_lights", + pp.objects_cut_predicted_paths_beyond_red_lights); + + updateParam(parameters, ns_ + ".overlap.minimum_distance", pp.overlap_min_dist); + updateParam(parameters, ns_ + ".overlap.extra_length", pp.overlap_extra_length); + + updateParam(parameters, ns_ + ".action.skip_if_over_max_decel", pp.skip_if_over_max_decel); + updateParam(parameters, ns_ + ".action.precision", pp.precision); + updateParam(parameters, ns_ + ".action.min_duration", pp.min_decision_duration); + updateParam(parameters, ns_ + ".action.distance_buffer", pp.dist_buffer); + updateParam(parameters, ns_ + ".action.slowdown.velocity", pp.slow_velocity); + updateParam(parameters, ns_ + ".action.slowdown.distance_threshold", pp.slow_dist_threshold); + updateParam(parameters, ns_ + ".action.stop.distance_threshold", pp.stop_dist_threshold); + + updateParam(parameters, ns_ + ".ego.min_assumed_velocity", pp.ego_min_velocity); + updateParam(parameters, ns_ + ".ego.extra_front_offset", pp.extra_front_offset); + updateParam(parameters, ns_ + ".ego.extra_rear_offset", pp.extra_rear_offset); + updateParam(parameters, ns_ + ".ego.extra_left_offset", pp.extra_left_offset); + updateParam(parameters, ns_ + ".ego.extra_right_offset", pp.extra_right_offset); +} + +VelocityPlanningResult OutOfLaneModule::plan( + const std::vector & ego_trajectory_points, + const std::shared_ptr planner_data) +{ + VelocityPlanningResult result; + tier4_autoware_utils::StopWatch stopwatch; + stopwatch.tic(); + out_of_lane::EgoData ego_data; + ego_data.pose = planner_data->current_odometry->pose; + ego_data.trajectory_points = ego_trajectory_points; + ego_data.first_trajectory_idx = + motion_utils::findNearestSegmentIndex(ego_trajectory_points, ego_data.pose.position); + ego_data.velocity = planner_data->current_velocity->twist.linear.x; + ego_data.max_decel = planner_data->velocity_smoother_->getMinDecel(); + stopwatch.tic("calculate_trajectory_footprints"); + const auto current_ego_footprint = + out_of_lane::calculate_current_ego_footprint(ego_data, params_, true); + const auto trajectory_footprints = + out_of_lane::calculate_trajectory_footprints(ego_data, params_); + const auto calculate_trajectory_footprints_us = stopwatch.toc("calculate_trajectory_footprints"); + // Calculate lanelets to ignore and consider + stopwatch.tic("calculate_lanelets"); + const auto trajectory_lanelets = + out_of_lane::calculate_trajectory_lanelets(ego_data, planner_data->route_handler); + const auto ignored_lanelets = out_of_lane::calculate_ignored_lanelets( + ego_data, trajectory_lanelets, planner_data->route_handler, params_); + const auto other_lanelets = out_of_lane::calculate_other_lanelets( + ego_data, trajectory_lanelets, ignored_lanelets, planner_data->route_handler, params_); + const auto calculate_lanelets_us = stopwatch.toc("calculate_lanelets"); + + debug_data_.reset_data(); + debug_data_.trajectory_points = ego_trajectory_points; + debug_data_.footprints = trajectory_footprints; + debug_data_.trajectory_lanelets = trajectory_lanelets; + debug_data_.ignored_lanelets = ignored_lanelets; + debug_data_.other_lanelets = other_lanelets; + debug_data_.first_trajectory_idx = ego_data.first_trajectory_idx; + + if (params_.skip_if_already_overlapping) { + debug_data_.current_footprint = current_ego_footprint; + const auto overlapped_lanelet_it = + std::find_if(other_lanelets.begin(), other_lanelets.end(), [&](const auto & ll) { + return boost::geometry::intersects(ll.polygon2d().basicPolygon(), current_ego_footprint); + }); + if (overlapped_lanelet_it != other_lanelets.end()) { + debug_data_.current_overlapped_lanelets.push_back(*overlapped_lanelet_it); + RCLCPP_DEBUG(logger_, "Ego is already overlapping a lane, skipping the module\n"); + return result; + } + } + // Calculate overlapping ranges + stopwatch.tic("calculate_overlapping_ranges"); + const auto ranges = out_of_lane::calculate_overlapping_ranges( + trajectory_footprints, trajectory_lanelets, other_lanelets, params_); + const auto calculate_overlapping_ranges_us = stopwatch.toc("calculate_overlapping_ranges"); + // Calculate stop and slowdown points + out_of_lane::DecisionInputs inputs; + inputs.ranges = ranges; + inputs.ego_data = ego_data; + stopwatch.tic("filter_predicted_objects"); + inputs.objects = out_of_lane::filter_predicted_objects(planner_data, ego_data, params_); + const auto filter_predicted_objects_ms = stopwatch.toc("filter_predicted_objects"); + inputs.route_handler = planner_data->route_handler; + inputs.lanelets = other_lanelets; + stopwatch.tic("calculate_decisions"); + const auto decisions = out_of_lane::calculate_decisions(inputs, params_, logger_); + const auto calculate_decisions_us = stopwatch.toc("calculate_decisions"); + stopwatch.tic("calc_slowdown_points"); + if ( // reset the previous inserted point if the timer expired + prev_inserted_point_ && + (clock_->now() - prev_inserted_point_time_).seconds() > params_.min_decision_duration) + prev_inserted_point_.reset(); + auto point_to_insert = + out_of_lane::calculate_slowdown_point(ego_data, decisions, prev_inserted_point_, params_); + const auto calc_slowdown_points_us = stopwatch.toc("calc_slowdown_points"); + stopwatch.tic("insert_slowdown_points"); + debug_data_.slowdowns.clear(); + if ( // reset the timer if there is no previous inserted point or if we avoid the same lane + point_to_insert && + (!prev_inserted_point_ || prev_inserted_point_->slowdown.lane_to_avoid.id() == + point_to_insert->slowdown.lane_to_avoid.id())) + prev_inserted_point_time_ = clock_->now(); + // reuse previous stop point if there is no new one or if its velocity is not higher than the new + // one and its arc length is lower + const auto should_use_prev_inserted_point = [&]() { + if ( + point_to_insert && prev_inserted_point_ && + prev_inserted_point_->slowdown.velocity <= point_to_insert->slowdown.velocity) { + const auto arc_length = motion_utils::calcSignedArcLength( + ego_trajectory_points, 0LU, point_to_insert->point.pose.position); + const auto prev_arc_length = motion_utils::calcSignedArcLength( + ego_trajectory_points, 0LU, prev_inserted_point_->point.pose.position); + return prev_arc_length < arc_length; + } + return !point_to_insert && prev_inserted_point_; + }(); + if (should_use_prev_inserted_point) { + // if the trajectory changed the prev point is no longer on the trajectory so we project it + const auto insert_arc_length = motion_utils::calcSignedArcLength( + ego_trajectory_points, 0LU, prev_inserted_point_->point.pose.position); + prev_inserted_point_->point.pose = + motion_utils::calcInterpolatedPose(ego_trajectory_points, insert_arc_length); + point_to_insert = prev_inserted_point_; + } + if (point_to_insert) { + prev_inserted_point_ = point_to_insert; + RCLCPP_DEBUG(logger_, "Avoiding lane %lu", point_to_insert->slowdown.lane_to_avoid.id()); + debug_data_.slowdowns = {*point_to_insert}; + if (point_to_insert->slowdown.velocity == 0.0) + result.stop_points.push_back(point_to_insert->point.pose.position); + else + result.slowdown_intervals.emplace_back( + point_to_insert->point.pose.position, point_to_insert->point.pose.position, + point_to_insert->slowdown.velocity); + + const auto is_approaching = motion_utils::calcSignedArcLength( + ego_trajectory_points, ego_data.pose.position, + point_to_insert->point.pose.position) > 0.1 && + ego_data.velocity > 0.1; + const auto status = is_approaching ? motion_utils::VelocityFactor::APPROACHING + : motion_utils::VelocityFactor::STOPPED; + velocity_factor_interface_.set( + ego_trajectory_points, ego_data.pose, point_to_insert->point.pose, status, "out_of_lane"); + result.velocity_factor = velocity_factor_interface_.get(); + } else if (!decisions.empty()) { + RCLCPP_WARN(logger_, "Could not insert stop point (would violate max deceleration limits)"); + } + const auto insert_slowdown_points_us = stopwatch.toc("insert_slowdown_points"); + debug_data_.ranges = inputs.ranges; + + const auto total_time_us = stopwatch.toc(); + RCLCPP_DEBUG( + logger_, + "Total time = %2.2fus\n" + "\tcalculate_lanelets = %2.0fus\n" + "\tcalculate_trajectory_footprints = %2.0fus\n" + "\tcalculate_overlapping_ranges = %2.0fus\n" + "\tfilter_pred_objects = %2.0fus\n" + "\tcalculate_decisions = %2.0fus\n" + "\tcalc_slowdown_points = %2.0fus\n" + "\tinsert_slowdown_points = %2.0fus\n", + total_time_us, calculate_lanelets_us, calculate_trajectory_footprints_us, + calculate_overlapping_ranges_us, filter_predicted_objects_ms, calculate_decisions_us, + calc_slowdown_points_us, insert_slowdown_points_us); + debug_publisher_->publish(out_of_lane::debug::create_debug_marker_array(debug_data_)); + virtual_wall_marker_creator.add_virtual_walls( + out_of_lane::debug::create_virtual_walls(debug_data_, params_)); + virtual_wall_publisher_->publish(virtual_wall_marker_creator.create_markers(clock_->now())); + return result; +} + +} // namespace autoware::motion_velocity_planner + +#include +PLUGINLIB_EXPORT_CLASS( + autoware::motion_velocity_planner::OutOfLaneModule, + autoware::motion_velocity_planner::PluginModuleInterface) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp new file mode 100644 index 0000000000000..8a20d5c850a09 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.hpp @@ -0,0 +1,63 @@ +// 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 OUT_OF_LANE_MODULE_HPP_ +#define OUT_OF_LANE_MODULE_HPP_ + +#include "types.hpp" + +#include +#include +#include +#include + +#include +#include +#include + +#include + +#include +#include +#include + +namespace autoware::motion_velocity_planner +{ +class OutOfLaneModule : public PluginModuleInterface +{ +public: + void init(rclcpp::Node & node, const std::string & module_name) override; + void update_parameters(const std::vector & parameters) override; + VelocityPlanningResult plan( + const std::vector & ego_trajectory_points, + const std::shared_ptr planner_data) override; + std::string get_module_name() const override { return module_name_; } + +private: + void init_parameters(rclcpp::Node & node); + out_of_lane::PlannerParam params_; + + inline static const std::string ns_ = "out_of_lane"; + std::string module_name_; + std::optional prev_inserted_point_{}; + rclcpp::Clock::SharedPtr clock_{}; + rclcpp::Time prev_inserted_point_time_{}; + +protected: + // Debug + mutable out_of_lane::DebugData debug_data_; +}; +} // namespace autoware::motion_velocity_planner + +#endif // OUT_OF_LANE_MODULE_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.cpp new file mode 100644 index 0000000000000..f89c620b75fb6 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.cpp @@ -0,0 +1,127 @@ +// 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 "overlapping_range.hpp" + +#include +#include + +#include + +#include +#include + +#include + +namespace autoware::motion_velocity_planner::out_of_lane +{ + +Overlap calculate_overlap( + const lanelet::BasicPolygon2d & trajectory_footprint, + const lanelet::ConstLanelets & trajectory_lanelets, const lanelet::ConstLanelet & lanelet) +{ + Overlap overlap; + const auto & left_bound = lanelet.leftBound2d().basicLineString(); + const auto & right_bound = lanelet.rightBound2d().basicLineString(); + // TODO(Maxime): these intersects (for each trajectory footprint, for each lanelet) are too + // expensive + const auto overlap_left = boost::geometry::intersects(trajectory_footprint, left_bound); + const auto overlap_right = boost::geometry::intersects(trajectory_footprint, right_bound); + + lanelet::BasicPolygons2d overlapping_polygons; + if (overlap_left || overlap_right) + boost::geometry::intersection( + trajectory_footprint, lanelet.polygon2d().basicPolygon(), overlapping_polygons); + for (const auto & overlapping_polygon : overlapping_polygons) { + for (const auto & point : overlapping_polygon) { + if (overlap_left && overlap_right) + overlap.inside_distance = boost::geometry::distance(left_bound, right_bound); + else if (overlap_left) + overlap.inside_distance = + std::max(overlap.inside_distance, boost::geometry::distance(point, left_bound)); + else if (overlap_right) + overlap.inside_distance = + std::max(overlap.inside_distance, boost::geometry::distance(point, right_bound)); + geometry_msgs::msg::Pose p; + p.position.x = point.x(); + p.position.y = point.y(); + const auto length = lanelet::utils::getArcCoordinates(trajectory_lanelets, p).length; + if (length > overlap.max_arc_length) { + overlap.max_arc_length = length; + overlap.max_overlap_point = point; + } + if (length < overlap.min_arc_length) { + overlap.min_arc_length = length; + overlap.min_overlap_point = point; + } + } + } + return overlap; +} + +OverlapRanges calculate_overlapping_ranges( + const std::vector & trajectory_footprints, + const lanelet::ConstLanelets & trajectory_lanelets, const lanelet::ConstLanelet & lanelet, + const PlannerParam & params) +{ + OverlapRanges ranges; + OtherLane other_lane(lanelet); + std::vector overlaps; + for (auto i = 0UL; i < trajectory_footprints.size(); ++i) { + const auto overlap = calculate_overlap(trajectory_footprints[i], trajectory_lanelets, lanelet); + const auto has_overlap = overlap.inside_distance > params.overlap_min_dist; + if (has_overlap) { // open/update the range + overlaps.push_back(overlap); + if (!other_lane.range_is_open) { + other_lane.first_range_bound.index = i; + other_lane.first_range_bound.point = overlap.min_overlap_point; + other_lane.first_range_bound.arc_length = + overlap.min_arc_length - params.overlap_extra_length; + other_lane.first_range_bound.inside_distance = overlap.inside_distance; + other_lane.range_is_open = true; + } + other_lane.last_range_bound.index = i; + other_lane.last_range_bound.point = overlap.max_overlap_point; + other_lane.last_range_bound.arc_length = overlap.max_arc_length + params.overlap_extra_length; + other_lane.last_range_bound.inside_distance = overlap.inside_distance; + } else if (other_lane.range_is_open) { // !has_overlap: close the range if it is open + ranges.push_back(other_lane.close_range()); + ranges.back().debug.overlaps = overlaps; + overlaps.clear(); + } + } + // close the range if it is still open + if (other_lane.range_is_open) { + ranges.push_back(other_lane.close_range()); + ranges.back().debug.overlaps = overlaps; + overlaps.clear(); + } + return ranges; +} + +OverlapRanges calculate_overlapping_ranges( + const std::vector & trajectory_footprints, + const lanelet::ConstLanelets & trajectory_lanelets, const lanelet::ConstLanelets & lanelets, + const PlannerParam & params) +{ + OverlapRanges ranges; + for (auto & lanelet : lanelets) { + const auto lanelet_ranges = + calculate_overlapping_ranges(trajectory_footprints, trajectory_lanelets, lanelet, params); + ranges.insert(ranges.end(), lanelet_ranges.begin(), lanelet_ranges.end()); + } + return ranges; +} + +} // namespace autoware::motion_velocity_planner::out_of_lane diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.hpp new file mode 100644 index 0000000000000..07c8663ea21bc --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/overlapping_range.hpp @@ -0,0 +1,63 @@ +// 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 OVERLAPPING_RANGE_HPP_ +#define OVERLAPPING_RANGE_HPP_ + +#include "types.hpp" + +#include + +#include + +#include + +namespace autoware::motion_velocity_planner::out_of_lane +{ + +/// @brief calculate the overlap between the given footprint and lanelet +/// @param [in] path_footprint footprint used to calculate the overlap +/// @param [in] trajectory_lanelets trajectory lanelets used to calculate arc length along the ego +/// trajectory +/// @param [in] lanelet lanelet used to calculate the overlap +/// @return the found overlap between the footprint and the lanelet +Overlap calculate_overlap( + const lanelet::BasicPolygon2d & trajectory_footprint, + const lanelet::ConstLanelets & trajectory_lanelets, const lanelet::ConstLanelet & lanelet); +/// @brief calculate the overlapping ranges between the trajectory footprints and a lanelet +/// @param [in] trajectory_footprints footprints used to calculate the overlaps +/// @param [in] trajectory_lanelets trajectory lanelets used to calculate arc length along the ego +/// trajectory +/// @param [in] lanelet lanelet used to calculate the overlaps +/// @param [in] params parameters +/// @return the overlapping ranges found between the footprints and the lanelet +OverlapRanges calculate_overlapping_ranges( + const std::vector & trajectory_footprints, + const lanelet::ConstLanelets & trajectory_lanelets, const lanelet::ConstLanelet & lanelet, + const PlannerParam & params); +/// @brief calculate the overlapping ranges between the trajectory footprints and some lanelets +/// @param [in] trajectory_footprints footprints used to calculate the overlaps +/// @param [in] trajectory_lanelets trajectory lanelets used to calculate arc length along the ego +/// trajectory +/// @param [in] lanelets lanelets used to calculate the overlaps +/// @param [in] params parameters +/// @return the overlapping ranges found between the footprints and the lanelets, sorted by +/// increasing arc length along the trajectory +OverlapRanges calculate_overlapping_ranges( + const std::vector & trajectory_footprints, + const lanelet::ConstLanelets & trajectory_lanelets, const lanelet::ConstLanelets & lanelets, + const PlannerParam & params); +} // namespace autoware::motion_velocity_planner::out_of_lane + +#endif // OVERLAPPING_RANGE_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp new file mode 100644 index 0000000000000..04f9f1ccac4c2 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/types.hpp @@ -0,0 +1,236 @@ +// 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 TYPES_HPP_ +#define TYPES_HPP_ + +#include + +#include +#include +#include +#include + +#include + +#include +#include +#include +#include +#include +#include +#include + +namespace autoware::motion_velocity_planner::out_of_lane +{ +using autoware_auto_planning_msgs::msg::TrajectoryPoint; + +/// @brief parameters for the "out of lane" module +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 + + double time_threshold; // [s](mode="threshold") objects time threshold + double intervals_ego_buffer; // [s](mode="intervals") buffer to extend the ego time range + double intervals_obj_buffer; // [s](mode="intervals") buffer to extend the objects time range + double ttc_threshold; // [s](mode="ttc") threshold on time to collision between ego and an object + double ego_min_velocity; // [m/s] minimum velocity of ego used to calculate its ttc or time range + + bool objects_use_predicted_paths; // whether to use the objects' predicted paths + bool objects_cut_predicted_paths_beyond_red_lights; // whether to cut predicted paths beyond red + // lights' stop lines + double objects_min_vel; // [m/s] objects lower than this velocity will be ignored + double objects_min_confidence; // minimum confidence to consider a predicted path + double objects_dist_buffer; // [m] distance buffer used to determine if a collision will occur in + // the other lane + + double overlap_extra_length; // [m] extra length to add around an overlap range + double overlap_min_dist; // [m] min distance inside another lane to consider an overlap + // action to insert in the trajectory if an object causes a conflict at an overlap + bool skip_if_over_max_decel; // if true, skip the action if it causes more than the max decel + double dist_buffer; + double slow_velocity; + double slow_dist_threshold; + double stop_dist_threshold; + double precision; // [m] precision when inserting a stop pose in the trajectory + double min_decision_duration; // [s] minimum duration needed a decision can be canceled + // ego dimensions used to create its polygon footprint + double front_offset; // [m] front offset (from vehicle info) + double rear_offset; // [m] rear offset (from vehicle info) + double right_offset; // [m] right offset (from vehicle info) + double left_offset; // [m] left offset (from vehicle info) + double extra_front_offset; // [m] extra front distance + double extra_rear_offset; // [m] extra rear distance + double extra_right_offset; // [m] extra right distance + double extra_left_offset; // [m] extra left distance +}; + +struct EnterExitTimes +{ + double enter_time{}; + double exit_time{}; +}; +struct RangeTimes +{ + EnterExitTimes ego{}; + EnterExitTimes object{}; +}; + +/// @brief action taken by the "out of lane" module +struct Slowdown +{ + size_t target_trajectory_idx{}; // we want to slowdown before this trajectory index + double velocity{}; // desired slow down velocity + lanelet::ConstLanelet lane_to_avoid{}; // we want to slowdown before entering this lane +}; +/// @brief slowdown to insert in a trajectory +struct SlowdownToInsert +{ + Slowdown slowdown{}; + autoware_auto_planning_msgs::msg::TrajectoryPoint point{}; +}; + +/// @brief bound of an overlap range (either the first, or last bound) +struct RangeBound +{ + size_t index{}; + lanelet::BasicPoint2d point{}; + double arc_length{}; + double inside_distance{}; +}; + +/// @brief representation of an overlap between the ego footprint and some other lane +struct Overlap +{ + double inside_distance = 0.0; ///!< distance inside the overlap + double min_arc_length = std::numeric_limits::infinity(); + double max_arc_length = 0.0; + lanelet::BasicPoint2d min_overlap_point{}; ///!< point with min arc length + lanelet::BasicPoint2d max_overlap_point{}; ///!< point with max arc length +}; + +/// @brief range along the trajectory where ego overlaps another lane +struct OverlapRange +{ + lanelet::ConstLanelet lane{}; + size_t entering_trajectory_idx{}; + size_t exiting_trajectory_idx{}; + lanelet::BasicPoint2d entering_point{}; // pose of the overlapping point closest along the lane + lanelet::BasicPoint2d exiting_point{}; // pose of the overlapping point furthest along the lane + double inside_distance{}; // [m] how much ego footprint enters the lane + mutable struct + { + std::vector overlaps{}; + std::optional decision{}; + RangeTimes times{}; + std::optional object{}; + } debug; +}; +using OverlapRanges = std::vector; +/// @brief representation of a lane and its current overlap range +struct OtherLane +{ + bool range_is_open = false; + RangeBound first_range_bound{}; + RangeBound last_range_bound{}; + lanelet::ConstLanelet lanelet{}; + lanelet::BasicPolygon2d polygon{}; + + explicit OtherLane(lanelet::ConstLanelet ll) : lanelet(std::move(ll)) + { + polygon = lanelet.polygon2d().basicPolygon(); + } + + [[nodiscard]] OverlapRange close_range() + { + OverlapRange range; + range.lane = lanelet; + range.entering_trajectory_idx = first_range_bound.index; + range.entering_point = first_range_bound.point; + range.exiting_trajectory_idx = last_range_bound.index; + range.exiting_point = last_range_bound.point; + range.inside_distance = + std::max(first_range_bound.inside_distance, last_range_bound.inside_distance); + range_is_open = false; + last_range_bound = {}; + return range; + } +}; + +/// @brief data related to the ego vehicle +struct EgoData +{ + std::vector trajectory_points{}; + size_t first_trajectory_idx{}; + double velocity{}; // [m/s] + double max_decel{}; // [m/s²] + geometry_msgs::msg::Pose pose{}; +}; + +/// @brief data needed to make decisions +struct DecisionInputs +{ + OverlapRanges ranges{}; + EgoData ego_data{}; + autoware_auto_perception_msgs::msg::PredictedObjects objects{}; + std::shared_ptr route_handler{}; + lanelet::ConstLanelets lanelets{}; +}; + +/// @brief debug data +struct DebugData +{ + std::vector footprints; + std::vector slowdowns; + geometry_msgs::msg::Pose ego_pose; + OverlapRanges ranges; + lanelet::BasicPolygon2d current_footprint; + lanelet::ConstLanelets current_overlapped_lanelets; + lanelet::ConstLanelets trajectory_lanelets; + lanelet::ConstLanelets ignored_lanelets; + lanelet::ConstLanelets other_lanelets; + std::vector trajectory_points; + size_t first_trajectory_idx; + + size_t prev_footprints = 0; + size_t prev_slowdowns = 0; + size_t prev_ranges = 0; + size_t prev_current_overlapped_lanelets = 0; + size_t prev_ignored_lanelets = 0; + size_t prev_trajectory_lanelets = 0; + size_t prev_other_lanelets = 0; + void reset_data() + { + prev_footprints = footprints.size(); + footprints.clear(); + prev_slowdowns = slowdowns.size(); + slowdowns.clear(); + prev_ranges = ranges.size(); + ranges.clear(); + prev_current_overlapped_lanelets = current_overlapped_lanelets.size(); + current_overlapped_lanelets.clear(); + prev_ignored_lanelets = ignored_lanelets.size(); + ignored_lanelets.clear(); + prev_trajectory_lanelets = trajectory_lanelets.size(); + trajectory_lanelets.clear(); + prev_other_lanelets = other_lanelets.size(); + other_lanelets.clear(); + } +}; + +} // namespace autoware::motion_velocity_planner::out_of_lane + +#endif // TYPES_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/test/test_filter_predicted_objects.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/test/test_filter_predicted_objects.cpp new file mode 100644 index 0000000000000..4961cd064efaf --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/test/test_filter_predicted_objects.cpp @@ -0,0 +1,58 @@ +// 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 "../src/filter_predicted_objects.hpp" + +#include +#include +#include + +#include +#include + +TEST(TestCollisionDistance, CutPredictedPathBeyondLine) +{ + using autoware::motion_velocity_planner::out_of_lane::cut_predicted_path_beyond_line; + autoware_auto_perception_msgs::msg::PredictedPath predicted_path; + lanelet::BasicLineString2d stop_line; + double object_front_overhang = 0.0; + const auto eps = 1e-9; + + EXPECT_NO_THROW(cut_predicted_path_beyond_line(predicted_path, stop_line, object_front_overhang)); + + geometry_msgs::msg::Pose pose; + pose.position.x = 0.0; + pose.position.y = 0.0; + predicted_path.path.push_back(pose); + pose.position.y = 1.0; + predicted_path.path.push_back(pose); + pose.position.y = 2.0; + predicted_path.path.push_back(pose); + pose.position.y = 3.0; + predicted_path.path.push_back(pose); + + cut_predicted_path_beyond_line(predicted_path, stop_line, object_front_overhang); + EXPECT_EQ(predicted_path.path.size(), 4UL); + for (auto i = 0UL; i < predicted_path.path.size(); ++i) { + EXPECT_EQ(predicted_path.path[i].position.x, 0.0); + EXPECT_NEAR(predicted_path.path[i].position.y, static_cast(i), eps); + } + stop_line = {{-1.0, 2.0}, {1.0, 2.0}}; + cut_predicted_path_beyond_line(predicted_path, stop_line, object_front_overhang); + EXPECT_EQ(predicted_path.path.size(), 2UL); + for (auto i = 0UL; i < predicted_path.path.size(); ++i) { + EXPECT_EQ(predicted_path.path[i].position.x, 0.0); + EXPECT_NEAR(predicted_path.path[i].position.y, static_cast(i), eps); + } +} diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CMakeLists.txt b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CMakeLists.txt new file mode 100644 index 0000000000000..f1eb7ff047fdc --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CMakeLists.txt @@ -0,0 +1,14 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_motion_velocity_planner_common) + +find_package(autoware_cmake REQUIRED) + +autoware_package() + +# ament_auto_add_library(${PROJECT_NAME}_lib SHARED +# DIRECTORY src +# ) + +ament_auto_package(INSTALL_TO_SHARE + include +) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/planner_data.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/planner_data.hpp new file mode 100644 index 0000000000000..84591f9429a66 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/planner_data.hpp @@ -0,0 +1,106 @@ +// Copyright 2024 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 AUTOWARE_MOTION_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_ +#define AUTOWARE_MOTION_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_ + +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +namespace autoware::motion_velocity_planner +{ +struct TrafficSignalStamped +{ + builtin_interfaces::msg::Time stamp; + autoware_perception_msgs::msg::TrafficSignal signal; +}; +struct PlannerData +{ + explicit PlannerData(rclcpp::Node & node) + : vehicle_info_(vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo()) + { + } + + // msgs from callbacks that are used for data-ready + geometry_msgs::msg::PoseStamped::ConstSharedPtr current_odometry; + geometry_msgs::msg::TwistStamped::ConstSharedPtr current_velocity; + geometry_msgs::msg::AccelWithCovarianceStamped::ConstSharedPtr current_acceleration; + autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr predicted_objects; + pcl::PointCloud::ConstPtr no_ground_pointcloud; + nav_msgs::msg::OccupancyGrid::ConstSharedPtr occupancy_grid; + std::shared_ptr route_handler; + + // nearest search + double ego_nearest_dist_threshold; + double ego_nearest_yaw_threshold; + + // other internal data + // traffic_light_id_map_raw is the raw observation, while traffic_light_id_map_keep_last keeps the + // last observed infomation for UNKNOWN + std::map traffic_light_id_map_raw_; + std::map traffic_light_id_map_last_observed_; + std::optional external_velocity_limit; + tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr virtual_traffic_light_states; + + // velocity smoother + std::shared_ptr velocity_smoother_{}; + // parameters + vehicle_info_util::VehicleInfo vehicle_info_; + + /** + *@fn + *@brief queries the traffic signal information of given Id. if keep_last_observation = true, + *recent UNKNOWN observation is overwritten as the last non-UNKNOWN observation + */ + std::optional get_traffic_signal( + const lanelet::Id id, const bool keep_last_observation = false) const + { + const auto & traffic_light_id_map = + keep_last_observation ? traffic_light_id_map_last_observed_ : traffic_light_id_map_raw_; + if (traffic_light_id_map.count(id) == 0) { + return std::nullopt; + } + return std::make_optional(traffic_light_id_map.at(id)); + } +}; +} // namespace autoware::motion_velocity_planner + +#endif // AUTOWARE_MOTION_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/plugin_module_interface.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/plugin_module_interface.hpp new file mode 100644 index 0000000000000..9011d3fb7e079 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/plugin_module_interface.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 AUTOWARE_MOTION_VELOCITY_PLANNER_COMMON__PLUGIN_MODULE_INTERFACE_HPP_ +#define AUTOWARE_MOTION_VELOCITY_PLANNER_COMMON__PLUGIN_MODULE_INTERFACE_HPP_ + +#include "planner_data.hpp" +#include "velocity_planning_result.hpp" + +#include +#include + +#include + +#include +#include +#include + +namespace autoware::motion_velocity_planner +{ + +class PluginModuleInterface +{ +public: + virtual ~PluginModuleInterface() = default; + virtual void init(rclcpp::Node & node, const std::string & module_name) = 0; + virtual void update_parameters(const std::vector & parameters) = 0; + virtual VelocityPlanningResult plan( + const std::vector & ego_trajectory_points, + const std::shared_ptr planner_data) = 0; + virtual std::string get_module_name() const = 0; + motion_utils::VelocityFactorInterface velocity_factor_interface_; + rclcpp::Logger logger_ = rclcpp::get_logger(""); + rclcpp::Publisher::SharedPtr debug_publisher_; + rclcpp::Publisher::SharedPtr virtual_wall_publisher_; + motion_utils::VirtualWallMarkerCreator virtual_wall_marker_creator{}; +}; + +} // namespace autoware::motion_velocity_planner + +#endif // AUTOWARE_MOTION_VELOCITY_PLANNER_COMMON__PLUGIN_MODULE_INTERFACE_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/velocity_planning_result.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/velocity_planning_result.hpp new file mode 100644 index 0000000000000..9b011b74503f2 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/velocity_planning_result.hpp @@ -0,0 +1,50 @@ +// Copyright 2024 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 AUTOWARE_MOTION_VELOCITY_PLANNER_COMMON__VELOCITY_PLANNING_RESULT_HPP_ +#define AUTOWARE_MOTION_VELOCITY_PLANNER_COMMON__VELOCITY_PLANNING_RESULT_HPP_ + +#include + +#include +#include +#include + +#include +#include +#include + +namespace autoware::motion_velocity_planner +{ +struct SlowdownInterval +{ + SlowdownInterval( + const geometry_msgs::msg::Point & from_, const geometry_msgs::msg::Point & to_, + const double vel) + : from{from_}, to{to_}, velocity{vel} + { + } + geometry_msgs::msg::Point from{}; + geometry_msgs::msg::Point to{}; + double velocity{}; +}; +struct VelocityPlanningResult +{ + std::vector stop_points{}; + std::vector slowdown_intervals{}; + std::optional velocity_factor{}; +}; +} // namespace autoware::motion_velocity_planner + +#endif // AUTOWARE_MOTION_VELOCITY_PLANNER_COMMON__VELOCITY_PLANNING_RESULT_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml new file mode 100644 index 0000000000000..ad791d247ee11 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml @@ -0,0 +1,40 @@ + + + + autoware_motion_velocity_planner_common + 0.1.0 + Common functions and interfaces for motion_velocity_planner modules + + Maxime Clement + + Apache License 2.0 + + Maxime Clement + + ament_cmake_auto + autoware_cmake + eigen3_cmake_module + + autoware_auto_perception_msgs + autoware_auto_planning_msgs + behavior_velocity_planner_common + eigen + geometry_msgs + lanelet2_extension + libboost-dev + motion_utils + motion_velocity_smoother + rclcpp + route_handler + tier4_autoware_utils + tier4_planning_msgs + visualization_msgs + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/CMakeLists.txt b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/CMakeLists.txt new file mode 100644 index 0000000000000..0af4da6fd4426 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/CMakeLists.txt @@ -0,0 +1,48 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_motion_velocity_planner_node) + +find_package(autoware_cmake REQUIRED) +find_package(rosidl_default_generators REQUIRED) + +rosidl_generate_interfaces( + ${PROJECT_NAME} + "srv/LoadPlugin.srv" + "srv/UnloadPlugin.srv" + DEPENDENCIES +) + +autoware_package() + +ament_auto_add_library(${PROJECT_NAME}_lib SHARED + DIRECTORY src +) + +rclcpp_components_register_node(${PROJECT_NAME}_lib + PLUGIN "autoware::motion_velocity_planner::MotionVelocityPlannerNode" + EXECUTABLE ${PROJECT_NAME}_exe +) + +if(${rosidl_cmake_VERSION} VERSION_LESS 2.5.0) + rosidl_target_interfaces(${PROJECT_NAME}_lib + ${PROJECT_NAME} "rosidl_typesupport_cpp") +else() + rosidl_get_typesupport_target( + cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp") + target_link_libraries(${PROJECT_NAME}_lib "${cpp_typesupport_target}") +endif() + +if(BUILD_TESTING) + ament_add_ros_isolated_gtest(test_${PROJECT_NAME} + test/src/test_node_interface.cpp + ) + target_link_libraries(test_${PROJECT_NAME} + gtest_main + ${PROJECT_NAME}_lib + ) + target_include_directories(test_${PROJECT_NAME} PRIVATE src) +endif() + +ament_auto_package(INSTALL_TO_SHARE + launch + config +) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/README.md b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/README.md new file mode 100644 index 0000000000000..f8c5eb172abd2 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/README.md @@ -0,0 +1,58 @@ +# Motion Velocity Planner + +## Overview + +`motion_velocity_planner` is a planner to adjust the trajectory velocity based on the obstacles around the vehicle. +It loads modules as plugins. Please refer to the links listed below for detail on each module. + +![Architecture](./docs/MotionVelocityPlanner-InternalInterface.drawio.svg) + +- [Out of Lane](../autoware_motion_velocity_out_of_lane_module/README.md) + +Each module calculates stop and slow down points to be inserted in the ego trajectory. +These points are assumed to correspond to the `base_link` frame of the ego vehicle as it follows the trajectory. +This means that to stop before a wall, a stop point is inserted in the trajectory at a distance ahead of the wall equal to the vehicle front offset (wheelbase + front overhang, see the [vehicle dimensions](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-interfaces/components/vehicle-dimensions/). + +![set_stop_velocity](./docs/set_stop_velocity.drawio.svg) + +## Input topics + +| Name | Type | Description | +| -------------------------------------- | ---------------------------------------------------- | ----------------------------- | +| `~/input/trajectory` | autoware_auto_planning_msgs::msg::Trajectory | input trajectory | +| `~/input/vector_map` | autoware_auto_mapping_msgs::msg::HADMapBin | vector map | +| `~/input/vehicle_odometry` | nav_msgs::msg::Odometry | vehicle position and velocity | +| `~/input/accel` | geometry_msgs::msg::AccelWithCovarianceStamped | vehicle acceleration | +| `~/input/dynamic_objects` | autoware_auto_perception_msgs::msg::PredictedObjects | dynamic objects | +| `~/input/no_ground_pointcloud` | sensor_msgs::msg::PointCloud2 | obstacle pointcloud | +| `~/input/traffic_signals` | autoware_perception_msgs::msg::TrafficSignalArray | traffic light states | +| `~/input/virtual_traffic_light_states` | tier4_v2x_msgs::msg::VirtualTrafficLightStateArray | virtual traffic light states | +| `~/input/occupancy_grid` | nav_msgs::msg::OccupancyGrid | occupancy grid | + +## Output topics + +| Name | Type | Description | +| --------------------------- | ------------------------------------------------- | -------------------------------------------------- | +| `~/output/trajectory` | autoware_auto_planning_msgs::msg::Trajectory | Ego trajectory with updated velocity profile | +| `~/output/velocity_factors` | autoware_adapi_v1_msgs::msg::VelocityFactorsArray | factors causing change in the ego velocity profile | + +## Services + +| Name | Type | Description | +| ------------------------- | -------------------------------------------------------- | ---------------------------- | +| `~/service/load_plugin` | autoware_motion_velocity_planner_node::srv::LoadPlugin | To request loading a plugin | +| `~/service/unload_plugin` | autoware_motion_velocity_planner_node::srv::UnloadPlugin | To request unloaded a plugin | + +## Node parameters + +| Parameter | Type | Description | +| ---------------- | ---------------- | ---------------------- | +| `launch_modules` | vector\ | module names to launch | + +In addition, the following parameters should be provided to the node: + +- [nearest search parameters](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/planning/scenario_planning/common/nearest_search.param.yaml); +- [vehicle info parameters](https://github.com/autowarefoundation/sample_vehicle_launch/blob/main/sample_vehicle_description/config/vehicle_info.param.yaml); +- [common planning parameters](https://github.com/autowarefoundation/autoware_launch/blob/main/autoware_launch/config/planning/scenario_planning/common/common.param.yaml); +- [smoother parameters](https://autowarefoundation.github.io/autoware.universe/main/planning/motion_velocity_smoother/#parameters) +- Parameters of each plugin that will be loaded. diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/config/motion_velocity_planner.param.yaml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/config/motion_velocity_planner.param.yaml new file mode 100644 index 0000000000000..5b2fea537d4f7 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/config/motion_velocity_planner.param.yaml @@ -0,0 +1,3 @@ +/**: + ros__parameters: + smooth_velocity_before_planning: true # [-] if true, smooth the velocity profile of the input trajectory before planning diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/docs/MotionVelocityPlanner-InternalInterface.drawio.svg b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/docs/MotionVelocityPlanner-InternalInterface.drawio.svg new file mode 100644 index 0000000000000..ea3b7ad99d4e5 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/docs/MotionVelocityPlanner-InternalInterface.drawio.svg @@ -0,0 +1,538 @@ + + + + + + + + + + + + + + + +
+
+
+ ~/input/dynamic_objects +
+
+
+
+ +
+
+
+ + + + + + + + +
+
+
+ ~/input/vehicle_odometry +
+
+
+
+ +
+
+
+ + + + + + + + +
+
+
+ ~/input/trajectory +
+
+
+
+ +
+
+
+ + + + +
+
+
+ Trajectory +
+
+
+
+ +
+
+
+ + + + + + + + Motion Velocity Planner + + + + + + + + + +
+
+
+ PlanVelocity +
+
+
+
+ +
+
+
+ + + + + + + + +
+
+
+ Trajectory +
+
+
+
+ +
+
+
+ + + + + + + + +
+
+
+ + Updated +
+ Trajectory +
+
+
+
+
+ +
+
+
+ + + + + + + + +
+
+
+
Stop/Slowdown
+
+ points +
+
+
+
+
+
+ +
+
+
+ + + + + + + + +
+
+
+ Data +
+
+
+
+ +
+
+
+ + + + + + + +
+
+
+ Planner Data +
+
+
+
+ +
+
+
+ + + + + + + + Loaded Modules + + + + + + + + + + out_of_lane + + + + + + + + + + obstacle_velocity_limiter + + + + + + + + + + dynamic_obstacle_stop + + + + + + + + + +
+
+
...
+
+
+
+ +
+
+
+ + + + + + + +
+
+
+ Smooth Velocity +
+
+
+
+ +
+
+
+ + + + + + + + obstacle_stop + + + + + + + + + + +
+
+
+ ~/input/vector_map +
+
+
+
+ +
+
+
+ + + + + + + +
+
+
+ + ~/output/trajectory + +
+
+
+
+ +
+
+
+ + + + + + + + +
+
+
+ ... +
+
+
+
+ +
+
+
+
+
diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/docs/set_stop_velocity.drawio.svg b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/docs/set_stop_velocity.drawio.svg new file mode 100644 index 0000000000000..5ae7d7dbb5461 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/docs/set_stop_velocity.drawio.svg @@ -0,0 +1,197 @@ + + + + + + + + + + + +
+
+
+ +

+ + stop point + +

+
+
+
+
+
+ stop point +
+
+ + + + + + + + + +
+
+
+ +

+ + v + +

+
+
+
+
+
+ v +
+
+ + + + +
+
+
+ +

+ + x + +

+
+
+
+
+
+ x +
+
+ + + + +
+
+
+ +

+ + baselink to front + +

+
+
+
+
+
+ baselink to front +
+
+ + + + + + + + + + + + +
+
+
+ +

+ + output velocity + +

+
+
+
+
+
+ output velocity +
+
+ + + + + +
+
+
+ +

+ + reference velocity + +

+
+
+
+
+
+ reference velocity +
+
+ +
+ + + + Viewer does not support full SVG 1.1 + + +
diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/launch/motion_velocity_planner.launch.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/launch/motion_velocity_planner.launch.xml new file mode 100644 index 0000000000000..3732d86ef380a --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/launch/motion_velocity_planner.launch.xml @@ -0,0 +1,42 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml new file mode 100644 index 0000000000000..2b52610c0276a --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml @@ -0,0 +1,57 @@ + + + + autoware_motion_velocity_planner_node + 0.1.0 + Node of the motion_velocity_planner + + Maxime Clement + + Apache License 2.0 + + Maxime Clement + + ament_cmake_auto + autoware_cmake + eigen3_cmake_module + + rosidl_default_generators + + autoware_auto_mapping_msgs + autoware_auto_perception_msgs + autoware_auto_planning_msgs + autoware_motion_velocity_planner_common + diagnostic_msgs + eigen + geometry_msgs + lanelet2_extension + libboost-dev + motion_utils + motion_velocity_smoother + pcl_conversions + pluginlib + rclcpp + rclcpp_components + sensor_msgs + tf2 + tf2_eigen + tf2_geometry_msgs + tf2_ros + tier4_autoware_utils + tier4_planning_msgs + visualization_msgs + + rosidl_default_runtime + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + autoware_motion_velocity_out_of_lane_module + autoware_planning_test_manager + + rosidl_interface_packages + + + ament_cmake + + diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/schema/motion_velocity_planner.schema.json b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/schema/motion_velocity_planner.schema.json new file mode 100644 index 0000000000000..7db22e5e39d17 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/schema/motion_velocity_planner.schema.json @@ -0,0 +1,33 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for the Motion Velocity Planner", + "type": "object", + "definitions": { + "motion_velocity_planner": { + "type": "object", + "properties": { + "smooth_velocity_before_planning": { + "type": "boolean", + "default": true, + "description": "if true, smooth the velocity profile of the input trajectory before planning" + } + }, + "required": ["smooth_velocity_before_planning"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/motion_velocity_planner" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp new file mode 100644 index 0000000000000..c0373678270dd --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp @@ -0,0 +1,458 @@ +// 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 "node.hpp" + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include +#include + +#include +#include +#include + +namespace +{ +rclcpp::SubscriptionOptions create_subscription_options(rclcpp::Node * node_ptr) +{ + rclcpp::CallbackGroup::SharedPtr callback_group = + node_ptr->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + + auto sub_opt = rclcpp::SubscriptionOptions(); + sub_opt.callback_group = callback_group; + + return sub_opt; +} +} // namespace + +namespace autoware::motion_velocity_planner +{ +MotionVelocityPlannerNode::MotionVelocityPlannerNode(const rclcpp::NodeOptions & node_options) +: Node("motion_velocity_planner_node", node_options), + tf_buffer_(this->get_clock()), + tf_listener_(tf_buffer_), + planner_data_(*this) +{ + using std::placeholders::_1; + using std::placeholders::_2; + + // Subscribers + sub_trajectory_ = this->create_subscription( + "~/input/trajectory", 1, std::bind(&MotionVelocityPlannerNode::on_trajectory, this, _1), + create_subscription_options(this)); + sub_predicted_objects_ = + this->create_subscription( + "~/input/dynamic_objects", 1, + std::bind(&MotionVelocityPlannerNode::on_predicted_objects, this, _1), + create_subscription_options(this)); + sub_no_ground_pointcloud_ = this->create_subscription( + "~/input/no_ground_pointcloud", rclcpp::SensorDataQoS(), + std::bind(&MotionVelocityPlannerNode::on_no_ground_pointcloud, this, _1), + create_subscription_options(this)); + sub_vehicle_odometry_ = this->create_subscription( + "~/input/vehicle_odometry", 1, std::bind(&MotionVelocityPlannerNode::on_odometry, this, _1), + create_subscription_options(this)); + sub_acceleration_ = this->create_subscription( + "~/input/accel", 1, std::bind(&MotionVelocityPlannerNode::on_acceleration, this, _1), + create_subscription_options(this)); + sub_lanelet_map_ = this->create_subscription( + "~/input/vector_map", rclcpp::QoS(10).transient_local(), + std::bind(&MotionVelocityPlannerNode::on_lanelet_map, this, _1), + create_subscription_options(this)); + sub_traffic_signals_ = + this->create_subscription( + "~/input/traffic_signals", 1, + std::bind(&MotionVelocityPlannerNode::on_traffic_signals, this, _1), + create_subscription_options(this)); + sub_virtual_traffic_light_states_ = + this->create_subscription( + "~/input/virtual_traffic_light_states", 1, + std::bind(&MotionVelocityPlannerNode::on_virtual_traffic_light_states, this, _1), + create_subscription_options(this)); + sub_occupancy_grid_ = this->create_subscription( + "~/input/occupancy_grid", 1, std::bind(&MotionVelocityPlannerNode::on_occupancy_grid, this, _1), + create_subscription_options(this)); + + srv_load_plugin_ = create_service( + "~/service/load_plugin", std::bind(&MotionVelocityPlannerNode::on_load_plugin, this, _1, _2)); + srv_unload_plugin_ = create_service( + "~/service/unload_plugin", + std::bind(&MotionVelocityPlannerNode::on_unload_plugin, this, _1, _2)); + + // Publishers + trajectory_pub_ = + this->create_publisher("~/output/trajectory", 1); + velocity_factor_publisher_ = + this->create_publisher( + "~/output/velocity_factors", 1); + + // Parameters + smooth_velocity_before_planning_ = declare_parameter("smooth_velocity_before_planning"); + // nearest search + planner_data_.ego_nearest_dist_threshold = + declare_parameter("ego_nearest_dist_threshold"); + planner_data_.ego_nearest_yaw_threshold = declare_parameter("ego_nearest_yaw_threshold"); + // set velocity smoother param + set_velocity_smoother_params(); + + // Initialize PlannerManager + for (const auto & name : declare_parameter>("launch_modules")) { + // workaround: Since ROS 2 can't get empty list, launcher set [''] on the parameter. + if (name == "") { + break; + } + planner_manager_.load_module_plugin(*this, name); + } + + set_param_callback_ = this->add_on_set_parameters_callback( + std::bind(&MotionVelocityPlannerNode::on_set_param, this, std::placeholders::_1)); + + logger_configure_ = std::make_unique(this); + published_time_publisher_ = std::make_unique(this); +} + +void MotionVelocityPlannerNode::on_load_plugin( + const LoadPlugin::Request::SharedPtr request, + [[maybe_unused]] const LoadPlugin::Response::SharedPtr response) +{ + std::unique_lock lk(mutex_); + planner_manager_.load_module_plugin(*this, request->plugin_name); +} + +void MotionVelocityPlannerNode::on_unload_plugin( + const UnloadPlugin::Request::SharedPtr request, + [[maybe_unused]] const UnloadPlugin::Response::SharedPtr response) +{ + std::unique_lock lk(mutex_); + planner_manager_.unload_module_plugin(*this, request->plugin_name); +} + +// NOTE: argument planner_data must not be referenced for multithreading +bool MotionVelocityPlannerNode::is_data_ready() const +{ + const auto & d = planner_data_; + auto clock = *get_clock(); + const auto check_with_msg = [&](const auto ptr, const auto & msg) { + constexpr auto throttle_duration = 3000; // [ms] + if (!ptr) { + RCLCPP_INFO_THROTTLE(get_logger(), clock, throttle_duration, msg); + return false; + } + return true; + }; + + return check_with_msg(d.current_odometry, "Waiting for current odometry") && + check_with_msg(d.current_velocity, "Waiting for current velocity") && + check_with_msg(d.current_acceleration, "Waiting for current acceleration") && + check_with_msg(d.predicted_objects, "Waiting for predicted objects") && + check_with_msg(d.no_ground_pointcloud, "Waiting for pointcloud") && + check_with_msg(map_ptr_, "Waiting for the map") && + check_with_msg( + d.velocity_smoother_, "Waiting for the initialization of the velocity smoother") && + check_with_msg(d.occupancy_grid, "Waiting for the occupancy grid"); +} + +void MotionVelocityPlannerNode::on_occupancy_grid( + const nav_msgs::msg::OccupancyGrid::ConstSharedPtr msg) +{ + std::lock_guard lock(mutex_); + planner_data_.occupancy_grid = msg; +} + +void MotionVelocityPlannerNode::on_predicted_objects( + const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr msg) +{ + std::lock_guard lock(mutex_); + planner_data_.predicted_objects = msg; +} + +void MotionVelocityPlannerNode::on_no_ground_pointcloud( + const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg) +{ + geometry_msgs::msg::TransformStamped transform; + try { + transform = tf_buffer_.lookupTransform( + "map", msg->header.frame_id, msg->header.stamp, rclcpp::Duration::from_seconds(0.1)); + } catch (tf2::TransformException & e) { + RCLCPP_WARN(get_logger(), "no transform found for no_ground_pointcloud: %s", e.what()); + return; + } + + pcl::PointCloud pc; + pcl::fromROSMsg(*msg, pc); + + Eigen::Affine3f affine = tf2::transformToEigen(transform.transform).cast(); + pcl::PointCloud::Ptr pc_transformed(new pcl::PointCloud); + if (!pc.empty()) { + tier4_autoware_utils::transformPointCloud(pc, *pc_transformed, affine); + } + + { + std::lock_guard lock(mutex_); + planner_data_.no_ground_pointcloud = pc_transformed; + } +} + +void MotionVelocityPlannerNode::on_odometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg) +{ + std::lock_guard lock(mutex_); + + auto current_odometry = std::make_shared(); + current_odometry->header = msg->header; + current_odometry->pose = msg->pose.pose; + planner_data_.current_odometry = current_odometry; + + auto current_velocity = std::make_shared(); + current_velocity->header = msg->header; + current_velocity->twist = msg->twist.twist; + planner_data_.current_velocity = current_velocity; +} + +void MotionVelocityPlannerNode::on_acceleration( + const geometry_msgs::msg::AccelWithCovarianceStamped::ConstSharedPtr msg) +{ + std::lock_guard lock(mutex_); + planner_data_.current_acceleration = msg; +} + +void MotionVelocityPlannerNode::set_velocity_smoother_params() +{ + planner_data_.velocity_smoother_ = + std::make_shared(*this); +} + +void MotionVelocityPlannerNode::on_lanelet_map( + const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg) +{ + std::lock_guard lock(mutex_); + + map_ptr_ = msg; + has_received_map_ = true; +} + +void MotionVelocityPlannerNode::on_traffic_signals( + const autoware_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr msg) +{ + std::lock_guard lock(mutex_); + + // clear previous observation + planner_data_.traffic_light_id_map_raw_.clear(); + const auto traffic_light_id_map_last_observed_old = + planner_data_.traffic_light_id_map_last_observed_; + planner_data_.traffic_light_id_map_last_observed_.clear(); + for (const auto & signal : msg->signals) { + TrafficSignalStamped traffic_signal; + traffic_signal.stamp = msg->stamp; + traffic_signal.signal = signal; + planner_data_.traffic_light_id_map_raw_[signal.traffic_signal_id] = traffic_signal; + const bool is_unknown_observation = + std::any_of(signal.elements.begin(), signal.elements.end(), [](const auto & element) { + return element.color == autoware_perception_msgs::msg::TrafficSignalElement::UNKNOWN; + }); + // if the observation is UNKNOWN and past observation is available, only update the timestamp + // and keep the body of the info + const auto old_data = traffic_light_id_map_last_observed_old.find(signal.traffic_signal_id); + if (is_unknown_observation && old_data != traffic_light_id_map_last_observed_old.end()) { + // copy last observation + planner_data_.traffic_light_id_map_last_observed_[signal.traffic_signal_id] = + old_data->second; + // update timestamp + planner_data_.traffic_light_id_map_last_observed_[signal.traffic_signal_id].stamp = + msg->stamp; + } else { + planner_data_.traffic_light_id_map_last_observed_[signal.traffic_signal_id] = traffic_signal; + } + } +} + +void MotionVelocityPlannerNode::on_virtual_traffic_light_states( + const tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr msg) +{ + std::lock_guard lock(mutex_); + planner_data_.virtual_traffic_light_states = msg; +} + +void MotionVelocityPlannerNode::on_trajectory( + const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr input_trajectory_msg) +{ + std::unique_lock lk(mutex_); + + if (!is_data_ready()) { + return; + } + + if (input_trajectory_msg->points.empty()) { + RCLCPP_WARN(get_logger(), "Input trajectory message is empty"); + return; + } + + if (has_received_map_) { + planner_data_.route_handler = std::make_shared(*map_ptr_); + has_received_map_ = false; + } + + autoware::motion_velocity_planner::TrajectoryPoints input_trajectory_points{ + input_trajectory_msg->points.begin(), input_trajectory_msg->points.end()}; + + auto output_trajectory_msg = generate_trajectory(input_trajectory_points); + output_trajectory_msg.header = input_trajectory_msg->header; + + lk.unlock(); + + trajectory_pub_->publish(output_trajectory_msg); + published_time_publisher_->publish_if_subscribed( + trajectory_pub_, output_trajectory_msg.header.stamp); +} + +void MotionVelocityPlannerNode::insert_stop( + autoware_auto_planning_msgs::msg::Trajectory & trajectory, + const geometry_msgs::msg::Point & stop_point) const +{ + const auto seg_idx = motion_utils::findNearestSegmentIndex(trajectory.points, stop_point); + const auto insert_idx = motion_utils::insertTargetPoint(seg_idx, stop_point, trajectory.points); + if (insert_idx) { + for (auto idx = *insert_idx; idx < trajectory.points.size(); ++idx) + trajectory.points[idx].longitudinal_velocity_mps = 0.0; + } else { + RCLCPP_WARN(get_logger(), "Failed to insert stop point"); + } +} + +void MotionVelocityPlannerNode::insert_slowdown( + autoware_auto_planning_msgs::msg::Trajectory & trajectory, + const autoware::motion_velocity_planner::SlowdownInterval & slowdown_interval) const +{ + const auto from_seg_idx = + motion_utils::findNearestSegmentIndex(trajectory.points, slowdown_interval.from); + const auto from_insert_idx = + motion_utils::insertTargetPoint(from_seg_idx, slowdown_interval.from, trajectory.points); + const auto to_seg_idx = + motion_utils::findNearestSegmentIndex(trajectory.points, slowdown_interval.to); + const auto to_insert_idx = + motion_utils::insertTargetPoint(to_seg_idx, slowdown_interval.to, trajectory.points); + if (from_insert_idx && to_insert_idx) { + for (auto idx = *from_insert_idx; idx <= *to_insert_idx; ++idx) + trajectory.points[idx].longitudinal_velocity_mps = 0.0; + } else { + RCLCPP_WARN(get_logger(), "Failed to insert slowdown point"); + } +} + +autoware::motion_velocity_planner::TrajectoryPoints MotionVelocityPlannerNode::smooth_trajectory( + const autoware::motion_velocity_planner::TrajectoryPoints & trajectory_points, + const autoware::motion_velocity_planner::PlannerData & planner_data) const +{ + const geometry_msgs::msg::Pose current_pose = planner_data.current_odometry->pose; + const double v0 = planner_data.current_velocity->twist.linear.x; + const double a0 = planner_data.current_acceleration->accel.accel.linear.x; + const auto & external_v_limit = planner_data.external_velocity_limit; + const auto & smoother = planner_data.velocity_smoother_; + + const auto traj_lateral_acc_filtered = + smoother->applyLateralAccelerationFilter(trajectory_points); + + const auto traj_steering_rate_limited = + smoother->applySteeringRateLimit(traj_lateral_acc_filtered, false); + + // Resample trajectory with ego-velocity based interval distances + auto traj_resampled = smoother->resampleTrajectory( + traj_steering_rate_limited, v0, current_pose, planner_data.ego_nearest_dist_threshold, + planner_data.ego_nearest_yaw_threshold); + const size_t traj_resampled_closest = motion_utils::findFirstNearestIndexWithSoftConstraints( + traj_resampled, current_pose, planner_data.ego_nearest_dist_threshold, + planner_data.ego_nearest_yaw_threshold); + std::vector debug_trajectories; + // Clip trajectory from closest point + autoware::motion_velocity_planner::TrajectoryPoints clipped; + autoware::motion_velocity_planner::TrajectoryPoints traj_smoothed; + clipped.insert( + clipped.end(), traj_resampled.begin() + traj_resampled_closest, traj_resampled.end()); + if (!smoother->apply(v0, a0, clipped, traj_smoothed, debug_trajectories)) { + RCLCPP_ERROR(get_logger(), "failed to smooth"); + } + traj_smoothed.insert( + traj_smoothed.begin(), traj_resampled.begin(), traj_resampled.begin() + traj_resampled_closest); + + if (external_v_limit) { + motion_velocity_smoother::trajectory_utils::applyMaximumVelocityLimit( + traj_resampled_closest, traj_smoothed.size(), external_v_limit->max_velocity, traj_smoothed); + } + return traj_smoothed; +} + +autoware_auto_planning_msgs::msg::Trajectory MotionVelocityPlannerNode::generate_trajectory( + autoware::motion_velocity_planner::TrajectoryPoints input_trajectory_points) +{ + autoware_auto_planning_msgs::msg::Trajectory output_trajectory_msg; + output_trajectory_msg.points = {input_trajectory_points.begin(), input_trajectory_points.end()}; + if (smooth_velocity_before_planning_) + input_trajectory_points = smooth_trajectory(input_trajectory_points, planner_data_); + + const auto planning_results = planner_manager_.plan_velocities( + input_trajectory_points, std::make_shared(planner_data_)); + + autoware_adapi_v1_msgs::msg::VelocityFactorArray velocity_factors; + velocity_factors.header.frame_id = "map"; + velocity_factors.header.stamp = get_clock()->now(); + + for (const auto & planning_result : planning_results) { + for (const auto & stop_point : planning_result.stop_points) + insert_stop(output_trajectory_msg, stop_point); + for (const auto & slowdown_interval : planning_result.slowdown_intervals) + insert_slowdown(output_trajectory_msg, slowdown_interval); + if (planning_result.velocity_factor) + velocity_factors.factors.push_back(*planning_result.velocity_factor); + } + + velocity_factor_publisher_->publish(velocity_factors); + return output_trajectory_msg; +} + +rcl_interfaces::msg::SetParametersResult MotionVelocityPlannerNode::on_set_param( + const std::vector & parameters) +{ + using tier4_autoware_utils::updateParam; + + { + std::unique_lock lk(mutex_); // for planner_manager_ + planner_manager_.update_module_parameters(parameters); + } + + updateParam(parameters, "smooth_velocity_before_planning", smooth_velocity_before_planning_); + updateParam(parameters, "ego_nearest_dist_threshold", planner_data_.ego_nearest_dist_threshold); + updateParam(parameters, "ego_nearest_yaw_threshold", planner_data_.ego_nearest_yaw_threshold); + + set_velocity_smoother_params(); + + rcl_interfaces::msg::SetParametersResult result; + result.successful = true; + result.reason = "success"; + return result; +} +} // namespace autoware::motion_velocity_planner + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::motion_velocity_planner::MotionVelocityPlannerNode) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp new file mode 100644 index 0000000000000..ecf128bf9a012 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.hpp @@ -0,0 +1,140 @@ +// Copyright 2024 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 NODE_HPP_ +#define NODE_HPP_ + +#include "planner_manager.hpp" + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include + +namespace autoware::motion_velocity_planner +{ +using autoware_auto_mapping_msgs::msg::HADMapBin; +using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_motion_velocity_planner_node::srv::LoadPlugin; +using autoware_motion_velocity_planner_node::srv::UnloadPlugin; +using TrajectoryPoints = std::vector; + +class MotionVelocityPlannerNode : public rclcpp::Node +{ +public: + explicit MotionVelocityPlannerNode(const rclcpp::NodeOptions & node_options); + +private: + // tf + tf2_ros::Buffer tf_buffer_; + tf2_ros::TransformListener tf_listener_; + + // subscriber + rclcpp::Subscription::SharedPtr sub_trajectory_; + rclcpp::Subscription::SharedPtr + sub_predicted_objects_; + rclcpp::Subscription::SharedPtr sub_no_ground_pointcloud_; + rclcpp::Subscription::SharedPtr sub_vehicle_odometry_; + rclcpp::Subscription::SharedPtr sub_acceleration_; + rclcpp::Subscription::SharedPtr sub_lanelet_map_; + rclcpp::Subscription::SharedPtr + sub_traffic_signals_; + rclcpp::Subscription::SharedPtr + sub_virtual_traffic_light_states_; + rclcpp::Subscription::SharedPtr sub_occupancy_grid_; + + void on_trajectory( + const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr input_trajectory_msg); + void on_predicted_objects( + const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr msg); + void on_no_ground_pointcloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg); + void on_odometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg); + void on_acceleration(const geometry_msgs::msg::AccelWithCovarianceStamped::ConstSharedPtr msg); + void on_lanelet_map(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr msg); + void on_traffic_signals( + const autoware_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr msg); + void on_virtual_traffic_light_states( + const tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr msg); + void on_occupancy_grid(const nav_msgs::msg::OccupancyGrid::ConstSharedPtr msg); + + // publishers + rclcpp::Publisher::SharedPtr trajectory_pub_; + rclcpp::Publisher::SharedPtr debug_viz_pub_; + rclcpp::Publisher::SharedPtr + velocity_factor_publisher_; + + // parameters + rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr set_param_callback_; + bool smooth_velocity_before_planning_{}; + /// @brief set parameters of the velocity smoother + void set_velocity_smoother_params(); + + // members + PlannerData planner_data_; + MotionVelocityPlannerManager planner_manager_; + HADMapBin::ConstSharedPtr map_ptr_{nullptr}; + bool has_received_map_ = false; + + rclcpp::Service::SharedPtr srv_load_plugin_; + rclcpp::Service::SharedPtr srv_unload_plugin_; + void on_unload_plugin( + const UnloadPlugin::Request::SharedPtr request, + const UnloadPlugin::Response::SharedPtr response); + void on_load_plugin( + const LoadPlugin::Request::SharedPtr request, const LoadPlugin::Response::SharedPtr response); + rcl_interfaces::msg::SetParametersResult on_set_param( + const std::vector & parameters); + + // mutex for planner_data_ + std::mutex mutex_; + + // function + bool is_data_ready() const; + void insert_stop( + autoware_auto_planning_msgs::msg::Trajectory & trajectory, + const geometry_msgs::msg::Point & stop_point) const; + void insert_slowdown( + autoware_auto_planning_msgs::msg::Trajectory & trajectory, + const autoware::motion_velocity_planner::SlowdownInterval & slowdown_interval) const; + autoware::motion_velocity_planner::TrajectoryPoints smooth_trajectory( + const autoware::motion_velocity_planner::TrajectoryPoints & trajectory_points, + const autoware::motion_velocity_planner::PlannerData & planner_data) const; + autoware_auto_planning_msgs::msg::Trajectory generate_trajectory( + autoware::motion_velocity_planner::TrajectoryPoints input_trajectory_points); + + std::unique_ptr logger_configure_; + + std::unique_ptr published_time_publisher_; +}; +} // namespace autoware::motion_velocity_planner + +#endif // NODE_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp new file mode 100644 index 0000000000000..fa3a3b1ae5dcb --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp @@ -0,0 +1,83 @@ +// 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 "planner_manager.hpp" + +#include + +#include +#include + +namespace autoware::motion_velocity_planner +{ + +MotionVelocityPlannerManager::MotionVelocityPlannerManager() +: plugin_loader_( + "autoware_motion_velocity_planner_node", + "autoware::motion_velocity_planner::PluginModuleInterface") +{ +} + +void MotionVelocityPlannerManager::load_module_plugin(rclcpp::Node & node, const std::string & name) +{ + // Check if the plugin is already loaded. + if (plugin_loader_.isClassLoaded(name)) { + RCLCPP_WARN_STREAM(node.get_logger(), "The plugin '" << name << "' is already loaded."); + return; + } + if (plugin_loader_.isClassAvailable(name)) { + const auto plugin = plugin_loader_.createSharedInstance(name); + plugin->init(node, name); + + // register + loaded_plugins_.push_back(plugin); + RCLCPP_DEBUG_STREAM(node.get_logger(), "The scene plugin '" << name << "' is loaded."); + } else { + RCLCPP_ERROR_STREAM(node.get_logger(), "The scene plugin '" << name << "' is not available."); + } +} + +void MotionVelocityPlannerManager::unload_module_plugin( + rclcpp::Node & node, const std::string & name) +{ + auto it = std::remove_if(loaded_plugins_.begin(), loaded_plugins_.end(), [&](const auto plugin) { + return plugin->get_module_name() == name; + }); + + if (it == loaded_plugins_.end()) { + RCLCPP_WARN_STREAM( + node.get_logger(), + "The scene plugin '" << name << "' is not found in the registered modules."); + } else { + loaded_plugins_.erase(it, loaded_plugins_.end()); + RCLCPP_INFO_STREAM(node.get_logger(), "The scene plugin '" << name << "' is unloaded."); + } +} + +void MotionVelocityPlannerManager::update_module_parameters( + const std::vector & parameters) +{ + for (auto & plugin : loaded_plugins_) plugin->update_parameters(parameters); +} + +std::vector MotionVelocityPlannerManager::plan_velocities( + const std::vector & ego_trajectory_points, + const std::shared_ptr planner_data) +{ + std::vector results; + for (auto & plugin : loaded_plugins_) + results.push_back(plugin->plan(ego_trajectory_points, planner_data)); + return results; +} +} // namespace autoware::motion_velocity_planner diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.hpp new file mode 100644 index 0000000000000..a5e330535fc73 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.hpp @@ -0,0 +1,57 @@ +// Copyright 2024 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 PLANNER_MANAGER_HPP_ +#define PLANNER_MANAGER_HPP_ + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include +#include +#include + +namespace autoware::motion_velocity_planner +{ +class MotionVelocityPlannerManager +{ +public: + MotionVelocityPlannerManager(); + void load_module_plugin(rclcpp::Node & node, const std::string & name); + void unload_module_plugin(rclcpp::Node & node, const std::string & name); + void update_module_parameters(const std::vector & parameters); + std::vector plan_velocities( + const std::vector & ego_trajectory_points, + const std::shared_ptr planner_data); + +private: + pluginlib::ClassLoader plugin_loader_; + std::vector> loaded_plugins_; +}; +} // namespace autoware::motion_velocity_planner + +#endif // PLANNER_MANAGER_HPP_ diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/srv/LoadPlugin.srv b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/srv/LoadPlugin.srv new file mode 100644 index 0000000000000..7b9f08ab0ded8 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/srv/LoadPlugin.srv @@ -0,0 +1,3 @@ +string plugin_name +--- +bool success diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/srv/UnloadPlugin.srv b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/srv/UnloadPlugin.srv new file mode 100644 index 0000000000000..7b9f08ab0ded8 --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/srv/UnloadPlugin.srv @@ -0,0 +1,3 @@ +string plugin_name +--- +bool success diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/test/src/test_node_interface.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/test/src/test_node_interface.cpp new file mode 100644 index 0000000000000..3ad5bab8e070b --- /dev/null +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/test/src/test_node_interface.cpp @@ -0,0 +1,139 @@ +// 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 "node.hpp" + +#include +#include +#include + +#include + +#include + +using autoware::motion_velocity_planner::MotionVelocityPlannerNode; +using planning_test_utils::PlanningInterfaceTestManager; + +std::shared_ptr generateTestManager() +{ + auto test_manager = std::make_shared(); + + // set subscriber with topic name: motion_velocity_planner → test_node_ + test_manager->setTrajectorySubscriber("motion_velocity_planner_node/output/trajectory"); + + // set motion_velocity_planner node's input topic name(this topic is changed to test node) + test_manager->setTrajectoryInputTopicName("motion_velocity_planner_node/input/trajectory"); + + test_manager->setInitialPoseTopicName("motion_velocity_planner_node/input/vehicle_odometry"); + test_manager->setOdometryTopicName("motion_velocity_planner_node/input/vehicle_odometry"); + + return test_manager; +} + +std::shared_ptr generateNode() +{ + auto node_options = rclcpp::NodeOptions{}; + + const auto planning_test_utils_dir = + ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto motion_velocity_planner_dir = + ament_index_cpp::get_package_share_directory("autoware_motion_velocity_planner_node"); + const auto motion_velocity_smoother_dir = + ament_index_cpp::get_package_share_directory("motion_velocity_smoother"); + + const auto get_motion_velocity_module_config = [](const std::string & module) { + const auto package_name = "autoware_motion_velocity_" + module + "_module"; + const auto package_path = ament_index_cpp::get_package_share_directory(package_name); + return package_path + "/config/" + module + ".param.yaml"; + }; + + std::vector module_names; + module_names.emplace_back("autoware::motion_velocity_planner::OutOfLaneModule"); + + std::vector params; + params.emplace_back("launch_modules", module_names); + params.emplace_back("is_simulation", false); + node_options.parameter_overrides(params); + + test_utils::updateNodeOptions( + node_options, + {planning_test_utils_dir + "/config/test_common.param.yaml", + planning_test_utils_dir + "/config/test_nearest_search.param.yaml", + planning_test_utils_dir + "/config/test_vehicle_info.param.yaml", + motion_velocity_smoother_dir + "/config/default_motion_velocity_smoother.param.yaml", + motion_velocity_smoother_dir + "/config/Analytical.param.yaml", + motion_velocity_planner_dir + "/config/motion_velocity_planner.param.yaml", + get_motion_velocity_module_config("out_of_lane")}); + + return std::make_shared(node_options); +} + +void publishMandatoryTopics( + std::shared_ptr test_manager, + std::shared_ptr test_target_node) +{ + // publish necessary topics from test_manager + test_manager->publishTF(test_target_node, "/tf"); + test_manager->publishAcceleration(test_target_node, "motion_velocity_planner_node/input/accel"); + test_manager->publishPredictedObjects( + test_target_node, "motion_velocity_planner_node/input/dynamic_objects"); + test_manager->publishPointCloud( + test_target_node, "motion_velocity_planner_node/input/no_ground_pointcloud"); + test_manager->publishOdometry( + test_target_node, "motion_velocity_planner_node/input/vehicle_odometry"); + test_manager->publishAcceleration(test_target_node, "motion_velocity_planner_node/input/accel"); + test_manager->publishMap(test_target_node, "motion_velocity_planner_node/input/vector_map"); + test_manager->publishTrafficSignals( + test_target_node, "motion_velocity_planner_node/input/traffic_signals"); + test_manager->publishVirtualTrafficLightState( + test_target_node, "motion_velocity_planner_node/input/virtual_traffic_light_states"); + test_manager->publishOccupancyGrid( + test_target_node, "motion_velocity_planner_node/input/occupancy_grid"); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) +{ + rclcpp::init(0, nullptr); + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + + publishMandatoryTopics(test_manager, test_target_node); + + // test with nominal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalTrajectory(test_target_node)); + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + // test with empty trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithAbnormalTrajectory(test_target_node)); + rclcpp::shutdown(); +} + +TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose) +{ + rclcpp::init(0, nullptr); + + auto test_manager = generateTestManager(); + auto test_target_node = generateNode(); + publishMandatoryTopics(test_manager, test_target_node); + + // test for normal trajectory + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testWithNominalTrajectory(test_target_node)); + + // make sure motion_velocity_planner is running + EXPECT_GE(test_manager->getReceivedTopicNum(), 1); + + ASSERT_NO_THROW_WITH_ERROR_MSG(test_manager->testOffTrackFromTrajectory(test_target_node)); + + rclcpp::shutdown(); +} 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/src/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.cpp b/planning/motion_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.cpp index 2bcb31ff10969..9fa4d697f06cb 100644 --- a/planning/motion_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.cpp +++ b/planning/motion_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.cpp @@ -199,13 +199,12 @@ bool calcStopVelocityWithConstantJerkAccLimit( } // for debug - std::stringstream ss; + RCLCPP_DEBUG(rclcpp::get_logger("velocity_planning_utils"), "Calculate stop velocity."); for (unsigned int i = 0; i < ts.size(); ++i) { - ss << "t: " << ts.at(i) << ", x: " << xs.at(i) << ", v: " << vs.at(i) << ", a: " << as.at(i) - << ", j: " << js.at(i) << std::endl; + RCLCPP_DEBUG( + rclcpp::get_logger("velocity_planning_utils"), "--- t: %f, x: %f, v: %f, a: %f, j: %f", + ts.at(i), xs.at(i), vs.at(i), as.at(i), js.at(i)); } - RCLCPP_DEBUG( - rclcpp::get_logger("velocity_planning_utils"), "Calculate stop velocity. %s", ss.str().c_str()); const double a_target = 0.0; const double v_margin = 0.3; 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/include/obstacle_avoidance_planner/node.hpp b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp index 3677e6c5fb075..db17496288766 100644 --- a/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp +++ b/planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp @@ -22,6 +22,7 @@ #include "obstacle_avoidance_planner/type_alias.hpp" #include "rclcpp/rclcpp.hpp" #include "tier4_autoware_utils/ros/logger_level_configure.hpp" +#include "tier4_autoware_utils/ros/polling_subscriber.hpp" #include "vehicle_info_util/vehicle_info_util.hpp" #include @@ -83,16 +84,14 @@ class ObstacleAvoidancePlanner : public rclcpp::Node TrajectoryParam traj_param_{}; EgoNearestParam ego_nearest_param_{}; - // variables for subscribers - Odometry::ConstSharedPtr ego_state_ptr_; - // interface publisher rclcpp::Publisher::SharedPtr traj_pub_; rclcpp::Publisher::SharedPtr virtual_wall_pub_; // interface subscriber rclcpp::Subscription::SharedPtr path_sub_; - rclcpp::Subscription::SharedPtr odom_sub_; + tier4_autoware_utils::InterProcessPollingSubscriber ego_odom_sub_{ + this, "~/input/odometry"}; // debug publisher rclcpp::Publisher::SharedPtr debug_extended_traj_pub_; @@ -113,8 +112,9 @@ class ObstacleAvoidancePlanner : public rclcpp::Node void resetPreviousData(); // main functions - bool isDataReady(const Path & path, rclcpp::Clock clock) const; - PlannerData createPlannerData(const Path & path) const; + bool checkInputPath(const Path & path, rclcpp::Clock clock) const; + PlannerData createPlannerData( + const Path & path, const Odometry::ConstSharedPtr ego_odom_ptr) const; std::vector generateOptimizedTrajectory(const PlannerData & planner_data); std::vector extendTrajectory( const std::vector & traj_points, 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/src/node.cpp b/planning/obstacle_avoidance_planner/src/node.cpp index c1da988eb5c25..b05d3f9da0c57 100644 --- a/planning/obstacle_avoidance_planner/src/node.cpp +++ b/planning/obstacle_avoidance_planner/src/node.cpp @@ -95,8 +95,6 @@ ObstacleAvoidancePlanner::ObstacleAvoidancePlanner(const rclcpp::NodeOptions & n // interface subscriber path_sub_ = create_subscription( "~/input/path", 1, std::bind(&ObstacleAvoidancePlanner::onPath, this, std::placeholders::_1)); - odom_sub_ = create_subscription( - "~/input/odometry", 1, [this](const Odometry::ConstSharedPtr msg) { ego_state_ptr_ = msg; }); // debug publisher debug_extended_traj_pub_ = create_publisher("~/debug/extended_traj", 1); @@ -224,8 +222,16 @@ void ObstacleAvoidancePlanner::onPath(const Path::ConstSharedPtr path_ptr) time_keeper_ptr_->init(); time_keeper_ptr_->tic(__func__); - // check if data is ready and valid - if (!isDataReady(*path_ptr, *get_clock())) { + // check if input path is valid + if (!checkInputPath(*path_ptr, *get_clock())) { + return; + } + + // check if ego's odometry is valid + const auto ego_odom_ptr = ego_odom_sub_.takeData(); + if (!ego_odom_ptr) { + RCLCPP_INFO_SKIPFIRST_THROTTLE( + get_logger(), *get_clock(), 5000, "Waiting for ego pose and twist."); return; } @@ -245,7 +251,7 @@ void ObstacleAvoidancePlanner::onPath(const Path::ConstSharedPtr path_ptr) } // 1. create planner data - const auto planner_data = createPlannerData(*path_ptr); + const auto planner_data = createPlannerData(*path_ptr, ego_odom_ptr); // 2. generate optimized trajectory const auto optimized_traj_points = generateOptimizedTrajectory(planner_data); @@ -276,13 +282,8 @@ void ObstacleAvoidancePlanner::onPath(const Path::ConstSharedPtr path_ptr) published_time_publisher_->publish_if_subscribed(traj_pub_, output_traj_msg.header.stamp); } -bool ObstacleAvoidancePlanner::isDataReady(const Path & path, rclcpp::Clock clock) const +bool ObstacleAvoidancePlanner::checkInputPath(const Path & path, rclcpp::Clock clock) const { - if (!ego_state_ptr_) { - RCLCPP_INFO_SKIPFIRST_THROTTLE(get_logger(), clock, 5000, "Waiting for ego pose and twist."); - return false; - } - if (path.points.size() < 2) { RCLCPP_INFO_SKIPFIRST_THROTTLE(get_logger(), clock, 5000, "Path points size is less than 1."); return false; @@ -297,7 +298,8 @@ bool ObstacleAvoidancePlanner::isDataReady(const Path & path, rclcpp::Clock cloc return true; } -PlannerData ObstacleAvoidancePlanner::createPlannerData(const Path & path) const +PlannerData ObstacleAvoidancePlanner::createPlannerData( + const Path & path, const Odometry::ConstSharedPtr ego_odom_ptr) const { // create planner data PlannerData planner_data; @@ -305,8 +307,8 @@ PlannerData ObstacleAvoidancePlanner::createPlannerData(const Path & path) const planner_data.traj_points = trajectory_utils::convertToTrajectoryPoints(path.points); planner_data.left_bound = path.left_bound; planner_data.right_bound = path.right_bound; - planner_data.ego_pose = ego_state_ptr_->pose.pose; - planner_data.ego_vel = ego_state_ptr_->twist.twist.linear.x; + planner_data.ego_pose = ego_odom_ptr->pose.pose; + planner_data.ego_vel = ego_odom_ptr->twist.twist.linear.x; debug_data_ptr_->ego_pose = planner_data.ego_pose; return planner_data; 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/config/obstacle_cruise_planner.param.yaml b/planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml index bd9c5750af78f..2ccd000657948 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,8 @@ 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.3 # lateral margin between obstacle and trajectory band with ego's width + max_lat_margin: 0.3 # lateral margin between the obstacles except for unknown and ego's footprint + max_lat_margin_against_unknown: -0.3 # lateral margin between the unknown obstacles and ego's footprint 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/include/obstacle_cruise_planner/node.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp index c368265ea0f66..fd65446408db1 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 & objects, 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, @@ -194,6 +200,7 @@ class ObstacleCruisePlannerNode : public rclcpp::Node double prediction_resampling_time_horizon; // max lateral margin double max_lat_margin_for_stop; + double max_lat_margin_for_stop_against_unknown; double max_lat_margin_for_cruise; double max_lat_margin_for_slow_down; double lat_hysteresis_margin_for_slow_down; diff --git a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/polygon_utils.hpp b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/polygon_utils.hpp index 1d490abca291a..71d0f84637abc 100644 --- a/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/polygon_utils.hpp +++ b/planning/obstacle_cruise_planner/include/obstacle_cruise_planner/polygon_utils.hpp @@ -47,8 +47,7 @@ std::vector getCollisionPoints( const std::vector & traj_points, const std::vector & traj_polygons, const rclcpp::Time & obstacle_stamp, const PredictedPath & predicted_path, const Shape & shape, const rclcpp::Time & current_time, const bool is_driving_forward, - std::vector & collision_index, - const double max_lat_dist = std::numeric_limits::max(), + std::vector & collision_index, const double max_dist = std::numeric_limits::max(), const double max_prediction_time_for_collision_check = std::numeric_limits::max()); } // namespace polygon_utils 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/src/node.cpp b/planning/obstacle_cruise_planner/src/node.cpp index 43400acb86bd9..c5f0c73a13b78 100644 --- a/planning/obstacle_cruise_planner/src/node.cpp +++ b/planning/obstacle_cruise_planner/src/node.cpp @@ -247,6 +247,8 @@ ObstacleCruisePlannerNode::BehaviorDeterminationParam::BehaviorDeterminationPara max_lat_margin_for_stop = node.declare_parameter("behavior_determination.stop.max_lat_margin"); + max_lat_margin_for_stop_against_unknown = + node.declare_parameter("behavior_determination.stop.max_lat_margin_against_unknown"); max_lat_margin_for_cruise = node.declare_parameter("behavior_determination.cruise.max_lat_margin"); enable_yield = node.declare_parameter("behavior_determination.cruise.yield.enable_yield"); @@ -311,6 +313,9 @@ void ObstacleCruisePlannerNode::BehaviorDeterminationParam::onParam( tier4_autoware_utils::updateParam( parameters, "behavior_determination.stop.max_lat_margin", max_lat_margin_for_stop); + tier4_autoware_utils::updateParam( + parameters, "behavior_determination.stop.max_lat_margin_against_unknown", + max_lat_margin_for_stop_against_unknown); tier4_autoware_utils::updateParam( parameters, "behavior_determination.cruise.max_lat_margin", max_lat_margin_for_cruise); tier4_autoware_utils::updateParam( @@ -484,12 +489,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 +516,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 +639,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 +666,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) { @@ -677,8 +687,8 @@ std::vector ObstacleCruisePlannerNode::convertToObstacles( }(); const double max_lat_margin = std::max( - std::max(p.max_lat_margin_for_stop, p.max_lat_margin_for_cruise), - p.max_lat_margin_for_slow_down); + {p.max_lat_margin_for_stop, p.max_lat_margin_for_stop_against_unknown, + p.max_lat_margin_for_cruise, p.max_lat_margin_for_slow_down}); if (max_lat_margin < min_lat_dist_to_traj_poly) { RCLCPP_INFO_EXPRESSION( get_logger(), enable_debug_info_, @@ -745,14 +755,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 +788,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 +821,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 +837,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()); @@ -1074,7 +1084,11 @@ ObstacleCruisePlannerNode::createCollisionPointsForInsideCruiseObstacle( std::vector collision_index; const auto collision_points = polygon_utils::getCollisionPoints( traj_points, traj_polys, obstacle.stamp, resampled_predicted_path, obstacle.shape, now(), - is_driving_forward_, collision_index); + is_driving_forward_, collision_index, + calcObstacleMaxLength(obstacle.shape) + p.decimate_trajectory_step_length + + std::hypot( + vehicle_info_.vehicle_length_m, + vehicle_info_.vehicle_width_m * 0.5 + p.max_lat_margin_for_cruise)); return collision_points; } @@ -1114,7 +1128,10 @@ ObstacleCruisePlannerNode::createCollisionPointsForOutsideCruiseObstacle( const auto collision_points = polygon_utils::getCollisionPoints( traj_points, traj_polys, obstacle.stamp, resampled_predicted_path, obstacle.shape, now(), is_driving_forward_, collision_index, - vehicle_info_.vehicle_width_m + p.max_lat_margin_for_cruise, + calcObstacleMaxLength(obstacle.shape) + p.decimate_trajectory_step_length + + std::hypot( + vehicle_info_.vehicle_length_m, + vehicle_info_.vehicle_width_m * 0.5 + p.max_lat_margin_for_cruise), p.max_prediction_time_for_collision_check); if (collision_points.empty()) { // Ignore vehicle obstacles outside the trajectory without collision @@ -1151,8 +1168,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); @@ -1161,7 +1179,13 @@ std::optional ObstacleCruisePlannerNode::createStopObstacle( if (!isStopObstacle(obstacle.classification.label)) { return std::nullopt; } - if (p.max_lat_margin_for_stop < precise_lat_dist) { + + const double max_lat_margin_for_stop = + (obstacle.classification.label == ObjectClassification::UNKNOWN) + ? p.max_lat_margin_for_stop_against_unknown + : p.max_lat_margin_for_stop; + + if (precise_lat_dist > std::max(max_lat_margin_for_stop, 1e-3)) { return std::nullopt; } @@ -1190,7 +1214,11 @@ std::optional ObstacleCruisePlannerNode::createStopObstacle( std::vector collision_index; const auto collision_points = polygon_utils::getCollisionPoints( traj_points, traj_polys, obstacle.stamp, resampled_predicted_path, obstacle.shape, now(), - is_driving_forward_, collision_index); + is_driving_forward_, collision_index, + calcObstacleMaxLength(obstacle.shape) + p.decimate_trajectory_step_length + + std::hypot( + vehicle_info_.vehicle_length_m, + vehicle_info_.vehicle_width_m * 0.5 + max_lat_margin_for_stop)); if (collision_points.empty()) { RCLCPP_INFO_EXPRESSION( get_logger(), enable_debug_info_, @@ -1203,7 +1231,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_, @@ -1215,8 +1243,8 @@ 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); + const auto traj_polys_with_lat_margin = + createOneStepPolygons(traj_points, vehicle_info_, odometry.pose.pose, 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 +1259,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 +1314,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; @@ -1361,7 +1389,6 @@ void ObstacleCruisePlannerNode::checkConsistency( const auto current_closest_stop_obstacle = obstacle_cruise_utils::getClosestStopObstacle(stop_obstacles); - // If previous closest obstacle ptr is not set if (!prev_closest_stop_obstacle_ptr_) { if (current_closest_stop_obstacle) { prev_closest_stop_obstacle_ptr_ = @@ -1370,44 +1397,23 @@ void ObstacleCruisePlannerNode::checkConsistency( return; } - // Put previous closest target obstacle if necessary const auto predicted_object_itr = std::find_if( predicted_objects.objects.begin(), predicted_objects.objects.end(), [&](PredictedObject predicted_object) { return tier4_autoware_utils::toHexString(predicted_object.object_id) == prev_closest_stop_obstacle_ptr_->uuid; }); - - // If previous closest obstacle is not in the current perception lists - // just return the current target obstacles + // If previous closest obstacle disappear from the perception result, do nothing anymore. if (predicted_object_itr == predicted_objects.objects.end()) { return; } - // Previous closest obstacle is in the perception lists - const auto obstacle_itr = std::find_if( + const auto is_disappeared_from_stop_obstacle = std::none_of( stop_obstacles.begin(), stop_obstacles.end(), [&](const auto & obstacle) { return obstacle.uuid == prev_closest_stop_obstacle_ptr_->uuid; }); - - // Previous closest obstacle is both in the perception lists and target obstacles - if (obstacle_itr != stop_obstacles.end()) { - if (current_closest_stop_obstacle) { - if ((current_closest_stop_obstacle->uuid == prev_closest_stop_obstacle_ptr_->uuid)) { - // prev_closest_obstacle is current_closest_stop_obstacle just return the target - // obstacles(in target obstacles) - prev_closest_stop_obstacle_ptr_ = - std::make_shared(*current_closest_stop_obstacle); - } else { - // New obstacle becomes new stop obstacle - prev_closest_stop_obstacle_ptr_ = - std::make_shared(*current_closest_stop_obstacle); - } - } else { - // Previous closest stop obstacle becomes cruise obstacle - prev_closest_stop_obstacle_ptr_ = nullptr; - } - } else { - // prev obstacle is not in the target obstacles, but in the perception list + if (is_disappeared_from_stop_obstacle) { + // re-evaluate as a stop candidate, and overwrite the current decision if "maintain stop" + // condition is satisfied const double elapsed_time = (current_time - prev_closest_stop_obstacle_ptr_->stamp).seconds(); if ( predicted_object_itr->kinematics.initial_twist_with_covariance.twist.linear.x < @@ -1416,13 +1422,13 @@ void ObstacleCruisePlannerNode::checkConsistency( stop_obstacles.push_back(*prev_closest_stop_obstacle_ptr_); return; } + } - if (current_closest_stop_obstacle) { - prev_closest_stop_obstacle_ptr_ = - std::make_shared(*current_closest_stop_obstacle); - } else { - prev_closest_stop_obstacle_ptr_ = nullptr; - } + if (current_closest_stop_obstacle) { + prev_closest_stop_obstacle_ptr_ = + std::make_shared(*current_closest_stop_obstacle); + } else { + prev_closest_stop_obstacle_ptr_ = nullptr; } } @@ -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; } diff --git a/planning/obstacle_cruise_planner/src/polygon_utils.cpp b/planning/obstacle_cruise_planner/src/polygon_utils.cpp index fa5a96b934f7a..1bd2de0bd985c 100644 --- a/planning/obstacle_cruise_planner/src/polygon_utils.cpp +++ b/planning/obstacle_cruise_planner/src/polygon_utils.cpp @@ -44,18 +44,18 @@ PointWithStamp calcNearestCollisionPoint( return collision_points.at(min_idx); } -// NOTE: max_lat_dist is used for efficient calculation to suppress boost::geometry's polygon +// NOTE: max_dist is used for efficient calculation to suppress boost::geometry's polygon // calculation. std::optional>> getCollisionIndex( const std::vector & traj_points, const std::vector & traj_polygons, const geometry_msgs::msg::Pose & object_pose, const rclcpp::Time & object_time, - const Shape & object_shape, const double max_lat_dist = std::numeric_limits::max()) + const Shape & object_shape, const double max_dist = std::numeric_limits::max()) { const auto obj_polygon = tier4_autoware_utils::toPolygon2d(object_pose, object_shape); for (size_t i = 0; i < traj_polygons.size(); ++i) { const double approximated_dist = tier4_autoware_utils::calcDistance2d(traj_points.at(i).pose, object_pose); - if (approximated_dist > max_lat_dist) { + if (approximated_dist > max_dist) { continue; } 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/include/path_smoother/elastic_band_smoother.hpp b/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp index e0bdb326adb33..bc566fdfb96bf 100644 --- a/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp +++ b/planning/path_smoother/include/path_smoother/elastic_band_smoother.hpp @@ -22,6 +22,7 @@ #include "path_smoother/type_alias.hpp" #include "rclcpp/rclcpp.hpp" #include "tier4_autoware_utils/ros/logger_level_configure.hpp" +#include "tier4_autoware_utils/ros/polling_subscriber.hpp" #include @@ -72,9 +73,6 @@ class ElasticBandSmoother : public rclcpp::Node CommonParam common_param_{}; EgoNearestParam ego_nearest_param_{}; - // variables for subscribers - Odometry::ConstSharedPtr ego_state_ptr_; - // variables for previous information std::shared_ptr> prev_optimized_traj_points_ptr_; @@ -84,7 +82,7 @@ class ElasticBandSmoother : public rclcpp::Node // interface subscriber rclcpp::Subscription::SharedPtr path_sub_; - rclcpp::Subscription::SharedPtr odom_sub_; + tier4_autoware_utils::InterProcessPollingSubscriber odom_sub_{this, "~/input/odometry"}; // debug publisher rclcpp::Publisher::SharedPtr debug_extended_traj_pub_; @@ -104,7 +102,8 @@ class ElasticBandSmoother : public rclcpp::Node void resetPreviousData(); // main functions - bool isDataReady(const Path & path, rclcpp::Clock clock) const; + bool isDataReady( + const Path & path, const Odometry::ConstSharedPtr ego_state_ptr, rclcpp::Clock clock) const; void applyInputVelocity( std::vector & output_traj_points, const std::vector & input_traj_points, 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/src/elastic_band_smoother.cpp b/planning/path_smoother/src/elastic_band_smoother.cpp index 6fb732309da4b..75300286ac9dc 100644 --- a/planning/path_smoother/src/elastic_band_smoother.cpp +++ b/planning/path_smoother/src/elastic_band_smoother.cpp @@ -79,8 +79,6 @@ ElasticBandSmoother::ElasticBandSmoother(const rclcpp::NodeOptions & node_option // interface subscriber path_sub_ = create_subscription( "~/input/path", 1, std::bind(&ElasticBandSmoother::onPath, this, std::placeholders::_1)); - odom_sub_ = create_subscription( - "~/input/odometry", 1, [this](const Odometry::ConstSharedPtr msg) { ego_state_ptr_ = msg; }); // debug publisher debug_extended_traj_pub_ = create_publisher("~/debug/extended_traj", 1); @@ -156,7 +154,8 @@ void ElasticBandSmoother::onPath(const Path::ConstSharedPtr path_ptr) time_keeper_ptr_->tic(__func__); // check if data is ready and valid - if (!isDataReady(*path_ptr, *get_clock())) { + const auto ego_state_ptr = odom_sub_.takeData(); + if (!isDataReady(*path_ptr, ego_state_ptr, *get_clock())) { return; } @@ -181,7 +180,7 @@ void ElasticBandSmoother::onPath(const Path::ConstSharedPtr path_ptr) // 1. calculate trajectory with Elastic Band // 1.a check if replan (= optimization) is required PlannerData planner_data( - input_traj_points, ego_state_ptr_->pose.pose, ego_state_ptr_->twist.twist.linear.x); + input_traj_points, ego_state_ptr->pose.pose, ego_state_ptr->twist.twist.linear.x); const bool is_replan_required = [&]() { if (replan_checker_ptr_->isResetRequired(planner_data)) { // NOTE: always replan when resetting previous optimization @@ -195,7 +194,7 @@ void ElasticBandSmoother::onPath(const Path::ConstSharedPtr path_ptr) replan_checker_ptr_->updateData(planner_data, is_replan_required, now()); time_keeper_ptr_->tic(__func__); auto smoothed_traj_points = is_replan_required ? eb_path_smoother_ptr_->smoothTrajectory( - input_traj_points, ego_state_ptr_->pose.pose) + input_traj_points, ego_state_ptr->pose.pose) : *prev_optimized_traj_points_ptr_; time_keeper_ptr_->toc(__func__, " "); @@ -203,7 +202,7 @@ void ElasticBandSmoother::onPath(const Path::ConstSharedPtr path_ptr) std::make_shared>(smoothed_traj_points); // 2. update velocity - applyInputVelocity(smoothed_traj_points, input_traj_points, ego_state_ptr_->pose.pose); + applyInputVelocity(smoothed_traj_points, input_traj_points, ego_state_ptr->pose.pose); // 3. extend trajectory to connect the optimized trajectory and the following path smoothly auto full_traj_points = extendTrajectory(input_traj_points, smoothed_traj_points); @@ -230,9 +229,10 @@ void ElasticBandSmoother::onPath(const Path::ConstSharedPtr path_ptr) published_time_publisher_->publish_if_subscribed(path_pub_, path_ptr->header.stamp); } -bool ElasticBandSmoother::isDataReady(const Path & path, rclcpp::Clock clock) const +bool ElasticBandSmoother::isDataReady( + const Path & path, const Odometry::ConstSharedPtr ego_state_ptr, rclcpp::Clock clock) const { - if (!ego_state_ptr_) { + if (!ego_state_ptr) { RCLCPP_INFO_SKIPFIRST_THROTTLE(get_logger(), clock, 5000, "Waiting for ego pose and twist."); return false; } 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..ce746352bb89c 100644 --- a/planning/planning_test_utils/CMakeLists.txt +++ b/planning/planning_test_utils/CMakeLists.txt @@ -5,10 +5,25 @@ find_package(autoware_cmake REQUIRED) autoware_package() ament_auto_add_library(planning_test_utils SHARED - src/planning_interface_test_manager.cpp + src/planning_test_utils.cpp) + +ament_auto_add_library(mock_data_parser SHARED + src/mock_data_parser.cpp) + +target_link_libraries(mock_data_parser + yaml-cpp ) +if(BUILD_TESTING) + ament_add_ros_isolated_gtest(test_mock_data_parser + test/test_mock_data_parser.cpp) + + target_link_libraries(test_mock_data_parser + mock_data_parser) +endif() + ament_auto_package(INSTALL_TO_SHARE config test_map + test_data ) diff --git a/planning/planning_test_utils/README.md b/planning/planning_test_utils/README.md index 63f1bf53a4954..c064e5791a487 100644 --- a/planning/planning_test_utils/README.md +++ b/planning/planning_test_utils/README.md @@ -1,92 +1,40 @@ -# Planning Interface Test Manager +# Test Utils ## 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. +Several Autoware's components and modules have already adopted unit testing, so a common library to ease the process of writing unit tests is necessary. ## 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. +The objective of the `test_utils` is to develop a unit testing library for the Autoware components. This library will include -## Features +- commonly used functions +- input/mock data parser +- maps for testing +- common routes and mock data for testing. -### Confirmation of normal operation +## Available Maps -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. +The following maps are available [here](https://github.com/autowarefoundation/autoware.universe/tree/main/planning/planning_test_utils/test_map) -### Robustness confirmation for special inputs +### Common -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. +The common map contains multiple types of usable inputs, including shoulder lanes, intersections, and some regulatory elements. The common map is named `lanelet2_map.osm` in the folder. -(WIP) +![common](./images/common.png) -## Usage +### 2 km Straight -```cpp +The 2 km straight lanelet map consists of two lanes that run in the same direction. The map is named `2km_test.osm`. -TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) -{ - rclcpp::init(0, nullptr); +![two_km](./images/2km-test.png) - // instantiate test_manager with PlanningInterfaceTestManager type - auto test_manager = std::make_shared(); +The following illustrates the design of the map. - // 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"); +![straight_diagram](./images/2km-test.svg) - // 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"}); +## Example use cases - // instantiate the TargetNode with node_options - auto test_target_node = std::make_shared(node_options); +### Autoware Planning Test Manager - // 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) +The goal of the [Autoware Planning Test Manager](https://autowarefoundation.github.io/autoware.universe/main/planning/autoware_planning_test_manager/) is to test planning module nodes. The `PlanningInterfaceTestManager` class ([source code](https://github.com/autowarefoundation/autoware.universe/blob/main/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp)) creates wrapper functions based on the `test_utils` functions. diff --git a/planning/planning_test_utils/images/2km-test.png b/planning/planning_test_utils/images/2km-test.png new file mode 100644 index 0000000000000..297dc5a43865e Binary files /dev/null and b/planning/planning_test_utils/images/2km-test.png differ diff --git a/planning/planning_test_utils/images/2km-test.svg b/planning/planning_test_utils/images/2km-test.svg new file mode 100644 index 0000000000000..26632cdde9118 --- /dev/null +++ b/planning/planning_test_utils/images/2km-test.svg @@ -0,0 +1,505 @@ + + + + + + + + + + + + + + + + + + +
+
+
+ 25.0 meter +
+
+
+
+ +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 3.5 meter +
+
+
+
+ +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ 2000.0 meter +
+
+
+
+ +
+
+
+ + + + + + + + + +
+
+
+ 1.75 meter +
+
+
+
+ +
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+ pose +
+ (0.0, 0.0) +
+
+
+
+
+
+ +
+
+
+ + + + + + + + + +
+
+
+ 1000.0 meter +
+
+
+
+ +
+
+
+ + + + + + + + + + + + +
+
+
+ 7.0 meter +
+
+
+
+ +
+
+
+ + + + + + + + + +
+
+
+ 25.0 meter +
+
+
+
+ +
+
+
+ + + + + + + + + +
+
+
+ 25.0 meter +
+
+
+
+ +
+
+
+ + + + + + + +
+
+
+ pose +
+ (1000.0, -3.5) +
+
+
+
+
+
+ +
+
+
+ + + + + + + + + + + + + + + +
+
+
+ pose +
+ (1000.0, 3.5) +
+
+
+
+
+
+ +
+
+
+ + + + + + + + + + + + + + + +
+
+
+ pose +
+ (-1000.0, 3.5) +
+
+
+
+
+
+ +
+
+
+
+
diff --git a/planning/planning_test_utils/images/common.png b/planning/planning_test_utils/images/common.png new file mode 100644 index 0000000000000..340437b53c0f5 Binary files /dev/null and b/planning/planning_test_utils/images/common.png differ diff --git a/planning/planning_test_utils/include/planning_test_utils/mock_data_parser.hpp b/planning/planning_test_utils/include/planning_test_utils/mock_data_parser.hpp new file mode 100644 index 0000000000000..09d4474dda15d --- /dev/null +++ b/planning/planning_test_utils/include/planning_test_utils/mock_data_parser.hpp @@ -0,0 +1,46 @@ +// Copyright 2024 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. + +#ifndef PLANNING_TEST_UTILS__MOCK_DATA_PARSER_HPP_ +#define PLANNING_TEST_UTILS__MOCK_DATA_PARSER_HPP_ + +#include +#include +#include +#include + +#include + +#include +#include + +namespace test_utils +{ +using autoware_planning_msgs::msg::LaneletPrimitive; +using autoware_planning_msgs::msg::LaneletRoute; +using autoware_planning_msgs::msg::LaneletSegment; +using geometry_msgs::msg::Pose; + +Pose parse_pose(const YAML::Node & node); + +LaneletPrimitive parse_lanelet_primitive(const YAML::Node & node); + +std::vector parse_lanelet_primitives(const YAML::Node & node); + +std::vector parse_segments(const YAML::Node & node); + +LaneletRoute parse_lanelet_route_file(const std::string & filename); +} // namespace test_utils + +#endif // PLANNING_TEST_UTILS__MOCK_DATA_PARSER_HPP_ 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_interface_test_manager_utils.hpp deleted file mode 100644 index 371a6316ce993..0000000000000 --- a/planning/planning_test_utils/include/planning_test_utils/planning_interface_test_manager_utils.hpp +++ /dev/null @@ -1,559 +0,0 @@ -// 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 PLANNING_TEST_UTILS__PLANNING_INTERFACE_TEST_MANAGER_UTILS_HPP_ -#define PLANNING_TEST_UTILS__PLANNING_INTERFACE_TEST_MANAGER_UTILS_HPP_ - -#include "ament_index_cpp/get_package_share_directory.hpp" -#include "rclcpp/rclcpp.hpp" - -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include - -namespace test_utils -{ -using autoware_adapi_v1_msgs::msg::OperationModeState; -using autoware_auto_mapping_msgs::msg::HADMapBin; -using autoware_auto_planning_msgs::msg::Path; -using autoware_auto_planning_msgs::msg::PathPointWithLaneId; -using autoware_auto_planning_msgs::msg::PathWithLaneId; -using autoware_auto_planning_msgs::msg::Trajectory; -using autoware_planning_msgs::msg::LaneletPrimitive; -using autoware_planning_msgs::msg::LaneletRoute; -using autoware_planning_msgs::msg::LaneletSegment; -using RouteSections = std::vector; -using geometry_msgs::msg::Point; -using geometry_msgs::msg::Pose; -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; -using tier4_autoware_utils::createQuaternionFromRPY; -using tier4_planning_msgs::msg::Scenario; -using unique_identifier_msgs::msg::UUID; - -geometry_msgs::msg::Pose createPose( - double x, double y, double z, double roll, double pitch, double yaw) -{ - geometry_msgs::msg::Pose p; - p.position = createPoint(x, y, z); - p.orientation = createQuaternionFromRPY(roll, pitch, yaw); - return p; -} - -geometry_msgs::msg::Pose createPose(const std::array & pose3d) -{ - return createPose(pose3d[0], pose3d[1], pose3d[2], 0.0, 0.0, pose3d[3]); -} - -template -T generateTrajectory( - const size_t num_points, const double point_interval, const double velocity = 0.0, - const double init_theta = 0.0, const double delta_theta = 0.0, - const size_t overlapping_point_index = std::numeric_limits::max()) -{ - using Point = typename T::_points_type::value_type; - - T traj; - for (size_t i = 0; i < num_points; ++i) { - const double theta = init_theta + i * delta_theta; - const double x = i * point_interval * std::cos(theta); - const double y = i * point_interval * std::sin(theta); - - Point p; - p.pose = createPose(x, y, 0.0, 0.0, 0.0, theta); - p.longitudinal_velocity_mps = velocity; - traj.points.push_back(p); - - if (i == overlapping_point_index) { - Point value_to_insert = traj.points[overlapping_point_index]; - traj.points.insert(traj.points.begin() + overlapping_point_index + 1, value_to_insert); - } - } - - return traj; -} - -LaneletSegment createLaneletSegment(int id) -{ - LaneletPrimitive primitive; - primitive.id = id; - primitive.primitive_type = "lane"; - LaneletSegment segment; - segment.preferred_primitive.id = id; - segment.primitives.push_back(primitive); - return segment; -} - -lanelet::LaneletMapPtr loadMap(const std::string & lanelet2_filename) -{ - lanelet::ErrorMessages errors{}; - lanelet::projection::MGRSProjector projector{}; - const lanelet::LaneletMapPtr map = lanelet::load(lanelet2_filename, projector, &errors); - if (errors.empty()) { - return map; - } - - for (const auto & error : errors) { - RCLCPP_ERROR_STREAM(rclcpp::get_logger("map_loader"), error); - } - return nullptr; -} - -HADMapBin convertToMapBinMsg( - const lanelet::LaneletMapPtr map, const std::string & lanelet2_filename, const rclcpp::Time & now) -{ - std::string format_version{}, map_version{}; - lanelet::io_handlers::AutowareOsmParser::parseVersions( - lanelet2_filename, &format_version, &map_version); - - HADMapBin map_bin_msg; - map_bin_msg.header.stamp = now; - map_bin_msg.header.frame_id = "map"; - map_bin_msg.format_version = format_version; - map_bin_msg.map_version = map_version; - lanelet::utils::conversion::toBinMsg(map, &map_bin_msg); - - return map_bin_msg; -} - -LaneletRoute makeNormalRoute() -{ - const std::array start_pose{5.5, 4., 0., M_PI_2}; - const std::array goal_pose{8.0, 26.3, 0, 0}; - LaneletRoute route; - route.header.frame_id = "map"; - route.start_pose = createPose(start_pose); - route.goal_pose = createPose(goal_pose); - return route; -} - -OccupancyGrid makeCostMapMsg(size_t width = 150, size_t height = 150, double resolution = 0.2) -{ - nav_msgs::msg::OccupancyGrid costmap_msg; - - // create info - costmap_msg.header.frame_id = "map"; - costmap_msg.info.width = width; - costmap_msg.info.height = height; - costmap_msg.info.resolution = resolution; - - // create data - const size_t n_elem = width * height; - for (size_t i = 0; i < n_elem; ++i) { - costmap_msg.data.push_back(0.0); - } - return costmap_msg; -} - -HADMapBin makeMapBinMsg() -{ - const auto planning_test_utils_dir = - ament_index_cpp::get_package_share_directory("planning_test_utils"); - const auto lanelet2_path = planning_test_utils_dir + "/test_map/lanelet2_map.osm"; - double center_line_resolution = 5.0; - // load map from file - const auto map = loadMap(lanelet2_path); - if (!map) { - return autoware_auto_mapping_msgs::msg::HADMapBin_>{}; - } - - // overwrite centerline - lanelet::utils::overwriteLaneletsCenterline(map, center_line_resolution, false); - - // create map bin msg - const auto map_bin_msg = - convertToMapBinMsg(map, lanelet2_path, rclcpp::Clock(RCL_ROS_TIME).now()); - return map_bin_msg; -} - -Odometry makeOdometry(const double shift = 0.0) -{ - Odometry odometry; - const std::array start_pose{0.0, shift, 0.0, 0.0}; - odometry.pose.pose = createPose(start_pose); - odometry.header.frame_id = "map"; - return odometry; -} - -Odometry makeInitialPose(const double shift = 0.0) -{ - Odometry current_odometry; - const auto yaw = 0.9724497591854532; - const auto shift_x = shift * std::sin(yaw); - const auto shift_y = shift * std::cos(yaw); - const std::array start_pose{ - 3722.16015625 + shift_x, 73723.515625 + shift_y, 0.233112560494183, yaw}; - current_odometry.pose.pose = test_utils::createPose(start_pose); - current_odometry.header.frame_id = "map"; - return current_odometry; -} - -TFMessage makeTFMsg( - rclcpp::Node::SharedPtr target_node, std::string frame_id = "", std::string child_frame_id = "") -{ - TFMessage tf_msg; - geometry_msgs::msg::Quaternion quaternion; - quaternion.x = 0.; - quaternion.y = 0.; - quaternion.z = 0.23311256049418302; - quaternion.w = 0.9724497591854532; - - TransformStamped tf; - tf.header.stamp = target_node->get_clock()->now(); - tf.header.frame_id = frame_id; - tf.child_frame_id = child_frame_id; - tf.transform.translation.x = 3722.16015625; - tf.transform.translation.y = 73723.515625; - tf.transform.translation.z = 0; - tf.transform.rotation = quaternion; - - tf_msg.transforms.emplace_back(std::move(tf)); - return tf_msg; -} - -Scenario makeScenarioMsg(const std::string scenario) -{ - Scenario scenario_msg; - scenario_msg.current_scenario = scenario; - scenario_msg.activating_scenarios = {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) -{ - RouteSections route_sections; - route_sections.reserve(route_sections1.size() + route_sections2.size()); - if (!route_sections1.empty()) { - // remove end route section because it is overlapping with first one in next route_section - route_sections.insert(route_sections.end(), route_sections1.begin(), route_sections1.end() - 1); - } - if (!route_sections2.empty()) { - route_sections.insert(route_sections.end(), route_sections2.begin(), route_sections2.end()); - } - 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() -{ - LaneletRoute route; - route.header.frame_id = "map"; - route.start_pose = - createPose({3722.16015625, 73723.515625, 0.233112560494183, 0.9724497591854532}); - route.goal_pose = - createPose({3778.362060546875, 73721.2734375, -0.5107480274693206, 0.8597304533609347}); - - std::vector primitive_ids = {9102, 9178, 54, 112}; - for (int id : primitive_ids) { - route.segments.push_back(createLaneletSegment(id)); - } - - std::array uuid_bytes{210, 87, 16, 126, 98, 151, 58, 28, - 252, 221, 230, 92, 122, 170, 46, 6}; - route.uuid.uuid = uuid_bytes; - - route.allow_modification = false; - return route; -} - -template -void createPublisherWithQoS( - rclcpp::Node::SharedPtr test_node, std::string topic_name, - std::shared_ptr> & publisher) -{ - if constexpr ( - std::is_same_v || std::is_same_v || - std::is_same_v) { - rclcpp::QoS qos(rclcpp::KeepLast(1)); - qos.reliable(); - qos.transient_local(); - publisher = rclcpp::create_publisher(test_node, topic_name, qos); - } else { - publisher = rclcpp::create_publisher(test_node, topic_name, 1); - } -} - -template -void setPublisher( - rclcpp::Node::SharedPtr test_node, std::string topic_name, - std::shared_ptr> & publisher) -{ - createPublisherWithQoS(test_node, topic_name, publisher); -} - -template -void createSubscription( - rclcpp::Node::SharedPtr test_node, std::string topic_name, - std::function callback, - std::shared_ptr> & subscriber) -{ - if constexpr (std::is_same_v) { - subscriber = test_node->create_subscription(topic_name, rclcpp::QoS{1}, callback); - } else { - subscriber = test_node->create_subscription(topic_name, 10, callback); - } -} - -template -void setSubscriber( - rclcpp::Node::SharedPtr test_node, std::string topic_name, - std::shared_ptr> & subscriber, size_t & count) -{ - createSubscription( - test_node, topic_name, [&count](const typename T::ConstSharedPtr) { count++; }, subscriber); -} - -void spinSomeNodes( - rclcpp::Node::SharedPtr test_node, rclcpp::Node::SharedPtr target_node, - const int repeat_count = 1) -{ - rclcpp::executors::SingleThreadedExecutor executor; - executor.add_node(test_node); - executor.add_node(target_node); - for (int i = 0; i < repeat_count; i++) { - executor.spin_some(std::chrono::milliseconds(100)); - rclcpp::sleep_for(std::chrono::milliseconds(100)); - } -} - -template -void publishToTargetNode( - rclcpp::Node::SharedPtr test_node, rclcpp::Node::SharedPtr target_node, std::string topic_name, - typename rclcpp::Publisher::SharedPtr publisher, T data, const int repeat_count = 3) -{ - if (topic_name.empty()) { - int status; - char * demangled_name = abi::__cxa_demangle(typeid(data).name(), nullptr, nullptr, &status); - if (status == 0) { - throw std::runtime_error(std::string("Topic name for ") + demangled_name + " is empty"); - } else { - throw std::runtime_error(std::string("Topic name for ") + typeid(data).name() + " is empty"); - } - } - - test_utils::setPublisher(test_node, topic_name, publisher); - publisher->publish(data); - - if (target_node->count_subscribers(topic_name) == 0) { - throw std::runtime_error("No subscriber for " + topic_name); - } - test_utils::spinSomeNodes(test_node, target_node, repeat_count); -} - -void updateNodeOptions( - rclcpp::NodeOptions & node_options, const std::vector & params_files) -{ - std::vector arguments; - arguments.push_back("--ros-args"); - arguments.push_back("--params-file"); - for (const auto & param_file : params_files) { - arguments.push_back(param_file.c_str()); - arguments.push_back("--params-file"); - } - arguments.pop_back(); - - node_options.arguments(std::vector{arguments.begin(), arguments.end()}); -} - -PathWithLaneId loadPathWithLaneIdInYaml() -{ - const auto planning_test_utils_dir = - ament_index_cpp::get_package_share_directory("planning_test_utils"); - const auto yaml_path = planning_test_utils_dir + "/config/path_with_lane_id_data.yaml"; - YAML::Node yaml_node = YAML::LoadFile(yaml_path); - PathWithLaneId path_msg; - - // Convert YAML data to PathWithLaneId message - // Fill the header - path_msg.header.stamp.sec = yaml_node["header"]["stamp"]["sec"].as(); - path_msg.header.stamp.nanosec = yaml_node["header"]["stamp"]["nanosec"].as(); - path_msg.header.frame_id = yaml_node["header"]["frame_id"].as(); - - // Fill the points - for (const auto & point_node : yaml_node["points"]) { - PathPointWithLaneId point; - // Fill the PathPoint data - point.point.pose.position.x = point_node["point"]["pose"]["position"]["x"].as(); - point.point.pose.position.y = point_node["point"]["pose"]["position"]["y"].as(); - point.point.pose.position.z = point_node["point"]["pose"]["position"]["z"].as(); - point.point.pose.orientation.x = point_node["point"]["pose"]["orientation"]["x"].as(); - point.point.pose.orientation.y = point_node["point"]["pose"]["orientation"]["y"].as(); - point.point.pose.orientation.z = point_node["point"]["pose"]["orientation"]["z"].as(); - point.point.pose.orientation.w = point_node["point"]["pose"]["orientation"]["w"].as(); - point.point.longitudinal_velocity_mps = - point_node["point"]["longitudinal_velocity_mps"].as(); - point.point.lateral_velocity_mps = point_node["point"]["lateral_velocity_mps"].as(); - point.point.heading_rate_rps = point_node["point"]["heading_rate_rps"].as(); - point.point.is_final = point_node["point"]["is_final"].as(); - // Fill the lane_ids - for (const auto & lane_id_node : point_node["lane_ids"]) { - point.lane_ids.push_back(lane_id_node.as()); - } - - path_msg.points.push_back(point); - } - - // Fill the left_bound - for (const auto & point_node : yaml_node["left_bound"]) { - Point point; - // Fill the Point data (left_bound) - point.x = point_node["x"].as(); - point.y = point_node["y"].as(); - point.z = point_node["z"].as(); - - path_msg.left_bound.push_back(point); - } - - // Fill the right_bound - for (const auto & point_node : yaml_node["right_bound"]) { - Point point; - // Fill the Point data - point.x = point_node["x"].as(); - point.y = point_node["y"].as(); - point.z = point_node["z"].as(); - - path_msg.right_bound.push_back(point); - } - return path_msg; -} - -} // namespace test_utils - -#endif // PLANNING_TEST_UTILS__PLANNING_INTERFACE_TEST_MANAGER_UTILS_HPP_ 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 new file mode 100644 index 0000000000000..43c3e029d4437 --- /dev/null +++ b/planning/planning_test_utils/include/planning_test_utils/planning_test_utils.hpp @@ -0,0 +1,482 @@ +// 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 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" + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace test_utils +{ +using autoware_adapi_v1_msgs::msg::OperationModeState; +using autoware_auto_mapping_msgs::msg::HADMapBin; +using autoware_auto_planning_msgs::msg::Path; +using autoware_auto_planning_msgs::msg::PathPointWithLaneId; +using autoware_auto_planning_msgs::msg::PathWithLaneId; +using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_planning_msgs::msg::LaneletPrimitive; +using autoware_planning_msgs::msg::LaneletRoute; +using autoware_planning_msgs::msg::LaneletSegment; +using RouteSections = std::vector; +using geometry_msgs::msg::Point; +using geometry_msgs::msg::Pose; +using geometry_msgs::msg::PoseStamped; +using geometry_msgs::msg::TransformStamped; +using nav_msgs::msg::OccupancyGrid; +using nav_msgs::msg::Odometry; +using sensor_msgs::msg::PointCloud2; +using tf2_msgs::msg::TFMessage; +using tier4_autoware_utils::createPoint; +using tier4_autoware_utils::createQuaternionFromRPY; +using tier4_planning_msgs::msg::Scenario; +using unique_identifier_msgs::msg::UUID; + +/** + * @brief Creates a Pose message with the specified position and orientation. + * + * This function initializes a geometry_msgs::msg::Pose message with the + * given position (x, y, z) and orientation (roll, pitch, yaw). + * + * @param x The x-coordinate of the position. + * @param y The y-coordinate of the position. + * @param z The z-coordinate of the position. + * @param roll The roll component of the orientation (in radians). + * @param pitch The pitch component of the orientation (in radians). + * @param yaw The yaw component of the orientation (in radians). + * @return A geometry_msgs::msg::Pose message with the specified position + * and orientation. + */ +geometry_msgs::msg::Pose createPose( + double x, double y, double z, double roll, double pitch, double yaw); + +/** + * @brief Creates a Pose message from a 4-element array representing a 3D pose. + * + * This function initializes a geometry_msgs::msg::Pose message using a + * std::array of four doubles, where the first three elements represent the + * position (x, y, z) and the fourth element represents the yaw orientation. + * The roll and pitch orientations are assumed to be zero. + * + * @param pose3d A std::array of four doubles representing the 3D pose. The + * first element is the x-coordinate, the second is the y-coordinate, the + * third is the z-coordinate, and the fourth is the yaw orientation. + * @return A geometry_msgs::msg::Pose message with the specified position + * and yaw orientation, with roll and pitch set to zero. + */ +geometry_msgs::msg::Pose createPose(const std::array & pose3d); + +/** + * @brief Creates a LaneletSegment with the specified ID. + * + * Initializes a LaneletSegment containing a single LaneletPrimitive with the + * given ID and a primitive type of "lane". + * + * @param id The ID for the LaneletPrimitive and preferred primitive. + * @return A LaneletSegment with the specified ID. + */ +LaneletSegment createLaneletSegment(int id); + +/** + * @brief Loads a Lanelet map from a specified file. + * + * This function loads a Lanelet2 map using the given filename. It uses the MGRS + * projector and checks for any errors during the loading process. If errors + * are found, they are logged, and the function returns nullptr. + * + * @param lanelet2_filename The filename of the Lanelet2 map to load. + * @return A LaneletMapPtr to the loaded map, or nullptr if there were errors. + */ +lanelet::LaneletMapPtr loadMap(const std::string & lanelet2_filename); + +/** + * @brief Converts a Lanelet map to a HADMapBin message. + * + * This function converts a given Lanelet map to a HADMapBin message. It also + * parses the format and map versions from the specified filename and includes + * them in the message. The timestamp for the message is set to the provided time. + * + * @param map The Lanelet map to convert. + * @param lanelet2_filename The filename of the Lanelet2 map, used to parse format and map versions. + * @param now The current time to set in the message header. + * @return A HADMapBin message containing the converted map data. + */ +HADMapBin convertToMapBinMsg( + const lanelet::LaneletMapPtr map, const std::string & lanelet2_filename, + const rclcpp::Time & now); + +/** + * @brief Creates a normal Lanelet route with predefined start and goal poses. + * + * This function initializes a LaneletRoute with a predefined start and goal pose. + * + * @return A LaneletRoute with the specified start and goal poses. + */ +LaneletRoute makeNormalRoute(); + +/** + * @brief Creates an OccupancyGrid message with the specified dimensions and resolution. + * + * This function initializes an OccupancyGrid message with given width, height, and resolution. + * All cells in the grid are initialized to zero. + * + * @param width The width of the occupancy grid. + * @param height The height of the occupancy grid. + * @param resolution The resolution of the occupancy grid. + * @return An OccupancyGrid message with the specified dimensions and resolution. + */ +OccupancyGrid makeCostMapMsg(size_t width = 150, size_t height = 150, double resolution = 0.2); + +/** + * @brief Creates a HADMapBin message from a Lanelet map file. + * + * This function loads a Lanelet map from the given file, overwrites the + * centerline with the specified resolution, and converts the map to a HADMapBin message. + * + * @param absolute_path The absolute path to the Lanelet2 map file. + * @param center_line_resolution The resolution for the centerline. + * @return A HADMapBin message containing the map data. + */ +HADMapBin make_map_bin_msg( + const std::string & absolute_path, const double center_line_resolution = 5.0); + +/** + * @brief Creates a HADMapBin message using a predefined Lanelet2 map file. + * + * This function loads a lanelet2_map.osm from the test_map folder in the + * planning_test_utils package, overwrites the centerline with a resolution of 5.0, + * and converts the map to a HADMapBin message. + * + * @return A HADMapBin message containing the map data. + */ +HADMapBin makeMapBinMsg(); + +/** + * @brief Creates an Odometry message with a specified shift. + * + * This function initializes an Odometry message with a pose shifted by the given amount at y + * direction. x pose, z pose, and yaw angle remains zero. + * + * @param shift The amount by which to shift the pose. + * @return An Odometry message with the specified shift. + */ +Odometry makeOdometry(const double shift = 0.0); + +/** + * @brief Creates an initial Odometry message with a specified shift. + * + * This function initializes an Odometry message with a pose shifted by the given amount, + * accounting for a specific yaw angle. + * + * @param shift The amount by which to shift the pose. + * @return An Odometry message with the specified shift. + */ +Odometry makeInitialPose(const double shift = 0.0); + +/** + * @brief Creates a TFMessage with the specified frame IDs. + * + * This function initializes a TFMessage with a transform containing the given frame IDs. + * The transform includes a specific translation and rotation. + * + * @param target_node The node to use for obtaining the current time. + * @param frame_id The ID of the parent frame. + * @param child_frame_id The ID of the child frame. + * @return A TFMessage containing the transform. + */ +TFMessage makeTFMsg( + rclcpp::Node::SharedPtr target_node, std::string && frame_id = "", + std::string && child_frame_id = ""); + +/** + * @brief Creates a Scenario message with the specified scenario. + * + * This function initializes a Scenario message with the current scenario and a list of activating + * scenarios. + * + * @param scenario The name of the current scenario. + * @return A Scenario message with the specified scenario. + */ +Scenario makeScenarioMsg(const std::string & scenario); + +/** + * @brief Combines two sets of consecutive RouteSections. + * + * This function combines two sets of RouteSections, removing the overlapping end section from the + * first set. + * + * @param route_sections1 The first set of RouteSections. + * @param route_sections2 The second set of RouteSections. + * @return A combined set of RouteSections. + */ +RouteSections combineConsecutiveRouteSections( + const RouteSections & route_sections1, const RouteSections & route_sections2); + +/** + * @brief Creates a predefined behavior Lanelet route. + * + * This function initializes a LaneletRoute with predefined start and goal poses, + * a list of lanelet segment IDs, and a fixed UUID. + * this is for the test lanelet2_map.osm + * file hash: a9f84cff03b55a64917bc066451276d2293b0a54f5c088febca0c7fdf2f245d5 + * + * @return A LaneletRoute with the specified attributes. + */ +LaneletRoute makeBehaviorNormalRoute(); + +/** + * @brief Spins multiple ROS nodes a specified number of times. + * + * This function spins the given test and target nodes for the specified number of iterations. + * + * @param test_node The test node to spin. + * @param target_node The target node to spin. + * @param repeat_count The number of times to spin the nodes. + */ +void spinSomeNodes( + rclcpp::Node::SharedPtr test_node, rclcpp::Node::SharedPtr target_node, + const int repeat_count = 1); + +/** + * @brief Updates node options with parameter files. + * + * This function updates the given node options to include the specified parameter files. + * + * @param node_options The node options to update. + * @param params_files A vector of parameter file paths to add to the node options. + */ +void updateNodeOptions( + rclcpp::NodeOptions & node_options, const std::vector & params_files); + +/** + * @brief Loads a PathWithLaneId message from a YAML file. + * + * This function loads a PathWithLaneId message from a YAML file located in the + * planning_test_utils package. + * + * @return A PathWithLaneId message containing the loaded data. + */ +PathWithLaneId loadPathWithLaneIdInYaml(); + +/** + * @brief Generates a trajectory with specified parameters. + * + * This function generates a trajectory of type T with a given number of points, + * point interval, velocity, initial theta, delta theta, and optionally an + * overlapping point index. + * + * @tparam T The type of the trajectory. + * @param num_points The number of points in the trajectory. + * @param point_interval The distance between consecutive points. + * @param velocity The longitudinal velocity for each point. + * @param init_theta The initial theta angle. + * @param delta_theta The change in theta per point. + * @param overlapping_point_index The index of the point to overlap (default is max size_t value). + * @return A trajectory of type T with the specified parameters. + */ +template +T generateTrajectory( + const size_t num_points, const double point_interval, const double velocity = 0.0, + const double init_theta = 0.0, const double delta_theta = 0.0, + const size_t overlapping_point_index = std::numeric_limits::max()) +{ + using Point = typename T::_points_type::value_type; + + T traj; + for (size_t i = 0; i < num_points; ++i) { + const double theta = init_theta + i * delta_theta; + const double x = i * point_interval * std::cos(theta); + const double y = i * point_interval * std::sin(theta); + + Point p; + p.pose = createPose(x, y, 0.0, 0.0, 0.0, theta); + p.longitudinal_velocity_mps = velocity; + traj.points.push_back(p); + + if (i == overlapping_point_index) { + Point value_to_insert = traj.points[overlapping_point_index]; + traj.points.insert(traj.points.begin() + overlapping_point_index + 1, value_to_insert); + } + } + + return traj; +} + +/** + * @brief Creates a publisher with appropriate QoS settings. + * + * This function creates a publisher for a given topic name and message type with appropriate + * QoS settings, depending on the message type. + * + * @tparam T The type of the message to publish. + * @param test_node The node to create the publisher on. + * @param topic_name The name of the topic to publish to. + * @param publisher A reference to the publisher to be created. + */ +template +void createPublisherWithQoS( + rclcpp::Node::SharedPtr test_node, std::string topic_name, + std::shared_ptr> & publisher) +{ + if constexpr ( + std::is_same_v || std::is_same_v || + std::is_same_v) { + rclcpp::QoS qos(rclcpp::KeepLast(1)); + qos.reliable(); + qos.transient_local(); + publisher = rclcpp::create_publisher(test_node, topic_name, qos); + } else { + publisher = rclcpp::create_publisher(test_node, topic_name, 1); + } +} + +/** + * @brief Sets up a publisher for a given topic. + * + * This function sets up a publisher for a given topic using createPublisherWithQoS. + * + * @tparam T The type of the message to publish. + * @param test_node The node to create the publisher on. + * @param topic_name The name of the topic to publish to. + * @param publisher A reference to the publisher to be set. + */ +template +void setPublisher( + rclcpp::Node::SharedPtr test_node, std::string topic_name, + std::shared_ptr> & publisher) +{ + createPublisherWithQoS(test_node, topic_name, publisher); +} + +/** + * @brief Creates a subscription with appropriate QoS settings. + * + * This function creates a subscription for a given topic name and message type with appropriate + * QoS settings, depending on the message type. + * + * @tparam T The type of the message to subscribe to. + * @param test_node The node to create the subscription on. + * @param topic_name The name of the topic to subscribe to. + * @param callback The callback function to call when a message is received. + * @param subscriber A reference to the subscription to be created. + */ +template +void createSubscription( + rclcpp::Node::SharedPtr test_node, std::string topic_name, + std::function callback, + std::shared_ptr> & subscriber) +{ + if constexpr (std::is_same_v) { + subscriber = test_node->create_subscription(topic_name, rclcpp::QoS{1}, callback); + } else { + subscriber = test_node->create_subscription(topic_name, 10, callback); + } +} + +/** + * @brief Sets up a subscriber for a given topic. + * + * This function sets up a subscriber for a given topic using createSubscription. + * + * @tparam T The type of the message to subscribe to. + * @param test_node The node to create the subscription on. + * @param topic_name The name of the topic to subscribe to. + * @param subscriber A reference to the subscription to be set. + * @param count A reference to a counter that increments on message receipt. + */ +template +void setSubscriber( + rclcpp::Node::SharedPtr test_node, std::string topic_name, + std::shared_ptr> & subscriber, size_t & count) +{ + createSubscription( + test_node, topic_name, [&count](const typename T::ConstSharedPtr) { count++; }, subscriber); +} + +/** + * @brief Publishes data to a target node. + * + * This function publishes data to a target node on a given topic, ensuring that the topic has + * subscribers and retrying a specified number of times. + * + * @tparam T The type of the message to publish. + * @param test_node The node to create the publisher on. + * @param target_node The target node to publish the message to. + * @param topic_name The name of the topic to publish to. + * @param publisher A shared pointer to the publisher. + * @param data The data to publish. + * @param repeat_count The number of times to retry publishing. + */ +template +void publishToTargetNode( + rclcpp::Node::SharedPtr test_node, rclcpp::Node::SharedPtr target_node, std::string topic_name, + typename rclcpp::Publisher::SharedPtr publisher, T data, const int repeat_count = 3) +{ + if (topic_name.empty()) { + int status = 1; + char * demangled_name = abi::__cxa_demangle(typeid(data).name(), nullptr, nullptr, &status); + if (status == 0) { + throw std::runtime_error(std::string("Topic name for ") + demangled_name + " is empty"); + } + throw std::runtime_error(std::string("Topic name for ") + typeid(data).name() + " is empty"); + } + + test_utils::setPublisher(test_node, topic_name, publisher); + publisher->publish(data); + + if (target_node->count_subscribers(topic_name) == 0) { + throw std::runtime_error("No subscriber for " + topic_name); + } + test_utils::spinSomeNodes(test_node, target_node, repeat_count); +} + +} // namespace test_utils + +#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..b236a64f48da0 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 @@ -23,10 +25,8 @@ component_interface_utils lanelet2_extension lanelet2_io - motion_utils nav_msgs rclcpp - route_handler tf2_msgs tf2_ros tier4_api_msgs diff --git a/planning/planning_test_utils/src/mock_data_parser.cpp b/planning/planning_test_utils/src/mock_data_parser.cpp new file mode 100644 index 0000000000000..f9f9a7b0b1594 --- /dev/null +++ b/planning/planning_test_utils/src/mock_data_parser.cpp @@ -0,0 +1,92 @@ +// Copyright 2024 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 "planning_test_utils/mock_data_parser.hpp" + +#include + +#include +#include +#include +#include + +#include + +#include +#include +#include + +namespace test_utils +{ +Pose parse_pose(const YAML::Node & node) +{ + Pose pose; + pose.position.x = node["position"]["x"].as(); + pose.position.y = node["position"]["y"].as(); + pose.position.z = node["position"]["z"].as(); + pose.orientation.x = node["orientation"]["x"].as(); + pose.orientation.y = node["orientation"]["y"].as(); + pose.orientation.z = node["orientation"]["z"].as(); + pose.orientation.w = node["orientation"]["w"].as(); + return pose; +} + +LaneletPrimitive parse_lanelet_primitive(const YAML::Node & node) +{ + LaneletPrimitive primitive; + primitive.id = node["id"].as(); + primitive.primitive_type = node["primitive_type"].as(); + + return primitive; +} + +std::vector parse_lanelet_primitives(const YAML::Node & node) +{ + std::vector primitives; + primitives.reserve(node.size()); + std::transform(node.begin(), node.end(), std::back_inserter(primitives), [&](const auto & p) { + return parse_lanelet_primitive(p); + }); + + return primitives; +} + +std::vector parse_segments(const YAML::Node & node) +{ + std::vector segments; + std::transform(node.begin(), node.end(), std::back_inserter(segments), [&](const auto & input) { + LaneletSegment segment; + segment.preferred_primitive = parse_lanelet_primitive(input["preferred_primitive"]); + segment.primitives = parse_lanelet_primitives(input["primitives"]); + return segment; + }); + + return segments; +} + +LaneletRoute parse_lanelet_route_file(const std::string & filename) +{ + LaneletRoute lanelet_route; + try { + YAML::Node config = YAML::LoadFile(filename); + + lanelet_route.start_pose = (config["start_pose"]) ? parse_pose(config["start_pose"]) : Pose(); + lanelet_route.goal_pose = (config["goal_pose"]) ? parse_pose(config["goal_pose"]) : Pose(); + lanelet_route.segments = parse_segments(config["segments"]); + } catch (const std::exception & e) { + RCLCPP_DEBUG(rclcpp::get_logger("planning_test_utils"), "Exception caught: %s", e.what()); + } + return lanelet_route; +} +} // namespace test_utils diff --git a/planning/planning_test_utils/src/planning_test_utils.cpp b/planning/planning_test_utils/src/planning_test_utils.cpp new file mode 100644 index 0000000000000..efed22855cf0f --- /dev/null +++ b/planning/planning_test_utils/src/planning_test_utils.cpp @@ -0,0 +1,313 @@ +// 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 "planning_test_utils/planning_test_utils.hpp" +namespace test_utils +{ + +geometry_msgs::msg::Pose createPose( + double x, double y, double z, double roll, double pitch, double yaw) +{ + geometry_msgs::msg::Pose p; + p.position = createPoint(x, y, z); + p.orientation = createQuaternionFromRPY(roll, pitch, yaw); + return p; +} + +geometry_msgs::msg::Pose createPose(const std::array & pose3d) +{ + return createPose(pose3d[0], pose3d[1], pose3d[2], 0.0, 0.0, pose3d[3]); +} + +LaneletSegment createLaneletSegment(int id) +{ + LaneletPrimitive primitive; + primitive.id = id; + primitive.primitive_type = "lane"; + LaneletSegment segment; + segment.preferred_primitive.id = id; + segment.primitives.push_back(primitive); + return segment; +} + +lanelet::LaneletMapPtr loadMap(const std::string & lanelet2_filename) +{ + lanelet::ErrorMessages errors{}; + lanelet::projection::MGRSProjector projector{}; + lanelet::LaneletMapPtr map = lanelet::load(lanelet2_filename, projector, &errors); + if (errors.empty()) { + return map; + } + + for (const auto & error : errors) { + RCLCPP_ERROR_STREAM(rclcpp::get_logger("map_loader"), error); + } + return nullptr; +} + +HADMapBin convertToMapBinMsg( + const lanelet::LaneletMapPtr map, const std::string & lanelet2_filename, const rclcpp::Time & now) +{ + std::string format_version{}; + std::string map_version{}; + lanelet::io_handlers::AutowareOsmParser::parseVersions( + lanelet2_filename, &format_version, &map_version); + + HADMapBin map_bin_msg; + map_bin_msg.header.stamp = now; + map_bin_msg.header.frame_id = "map"; + map_bin_msg.format_version = format_version; + map_bin_msg.map_version = map_version; + lanelet::utils::conversion::toBinMsg(map, &map_bin_msg); + + return map_bin_msg; +} + +LaneletRoute makeNormalRoute() +{ + const std::array start_pose{5.5, 4., 0., M_PI_2}; + const std::array goal_pose{8.0, 26.3, 0, 0}; + LaneletRoute route; + route.header.frame_id = "map"; + route.start_pose = createPose(start_pose); + route.goal_pose = createPose(goal_pose); + return route; +} + +OccupancyGrid makeCostMapMsg(size_t width, size_t height, double resolution) +{ + nav_msgs::msg::OccupancyGrid costmap_msg; + + // create info + costmap_msg.header.frame_id = "map"; + costmap_msg.info.width = width; + costmap_msg.info.height = height; + costmap_msg.info.resolution = static_cast(resolution); + + // create data + const size_t n_elem = width * height; + for (size_t i = 0; i < n_elem; ++i) { + costmap_msg.data.push_back(0.0); + } + return costmap_msg; +} + +HADMapBin make_map_bin_msg(const std::string & absolute_path, const double center_line_resolution) +{ + const auto map = loadMap(absolute_path); + if (!map) { + return autoware_auto_mapping_msgs::msg::HADMapBin_>{}; + } + + // overwrite centerline + lanelet::utils::overwriteLaneletsCenterline(map, center_line_resolution, false); + + // create map bin msg + const auto map_bin_msg = + convertToMapBinMsg(map, absolute_path, rclcpp::Clock(RCL_ROS_TIME).now()); + return map_bin_msg; +} + +HADMapBin makeMapBinMsg() +{ + const auto planning_test_utils_dir = + ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto lanelet2_path = planning_test_utils_dir + "/test_map/lanelet2_map.osm"; + double center_line_resolution = 5.0; + + return make_map_bin_msg(lanelet2_path, center_line_resolution); +} + +Odometry makeOdometry(const double shift) +{ + Odometry odometry; + const std::array start_pose{0.0, shift, 0.0, 0.0}; + odometry.pose.pose = createPose(start_pose); + odometry.header.frame_id = "map"; + return odometry; +} + +Odometry makeInitialPose(const double shift) +{ + Odometry current_odometry; + const auto yaw = 0.9724497591854532; + const auto shift_x = shift * std::sin(yaw); + const auto shift_y = shift * std::cos(yaw); + const std::array start_pose{ + 3722.16015625 + shift_x, 73723.515625 + shift_y, 0.233112560494183, yaw}; + current_odometry.pose.pose = test_utils::createPose(start_pose); + current_odometry.header.frame_id = "map"; + return current_odometry; +} + +TFMessage makeTFMsg( + rclcpp::Node::SharedPtr target_node, std::string && frame_id, std::string && child_frame_id) +{ + TFMessage tf_msg; + geometry_msgs::msg::Quaternion quaternion; + quaternion.x = 0.; + quaternion.y = 0.; + quaternion.z = 0.23311256049418302; + quaternion.w = 0.9724497591854532; + + TransformStamped tf; + tf.header.stamp = target_node->get_clock()->now(); + tf.header.frame_id = frame_id; + tf.child_frame_id = child_frame_id; + tf.transform.translation.x = 3722.16015625; + tf.transform.translation.y = 73723.515625; + tf.transform.translation.z = 0; + tf.transform.rotation = quaternion; + + tf_msg.transforms.emplace_back(std::move(tf)); + return tf_msg; +} + +Scenario makeScenarioMsg(const std::string & scenario) +{ + Scenario scenario_msg; + scenario_msg.current_scenario = scenario; + scenario_msg.activating_scenarios = {scenario}; + return scenario_msg; +} + +RouteSections combineConsecutiveRouteSections( + const RouteSections & route_sections1, const RouteSections & route_sections2) +{ + RouteSections route_sections; + route_sections.reserve(route_sections1.size() + route_sections2.size()); + if (!route_sections1.empty()) { + // remove end route section because it is overlapping with first one in next route_section + route_sections.insert(route_sections.end(), route_sections1.begin(), route_sections1.end() - 1); + } + if (!route_sections2.empty()) { + route_sections.insert(route_sections.end(), route_sections2.begin(), route_sections2.end()); + } + return route_sections; +} + +// this is for the test lanelet2_map.osm +// file hash: a9f84cff03b55a64917bc066451276d2293b0a54f5c088febca0c7fdf2f245d5 +LaneletRoute makeBehaviorNormalRoute() +{ + LaneletRoute route; + route.header.frame_id = "map"; + route.start_pose = + createPose({3722.16015625, 73723.515625, 0.233112560494183, 0.9724497591854532}); + route.goal_pose = + createPose({3778.362060546875, 73721.2734375, -0.5107480274693206, 0.8597304533609347}); + + std::vector primitive_ids = {9102, 9178, 54, 112}; + for (int id : primitive_ids) { + route.segments.push_back(createLaneletSegment(id)); + } + + std::array uuid_bytes{210, 87, 16, 126, 98, 151, 58, 28, + 252, 221, 230, 92, 122, 170, 46, 6}; + route.uuid.uuid = uuid_bytes; + + route.allow_modification = false; + return route; +} + +void spinSomeNodes( + rclcpp::Node::SharedPtr test_node, rclcpp::Node::SharedPtr target_node, const int repeat_count) +{ + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(test_node); + executor.add_node(target_node); + for (int i = 0; i < repeat_count; i++) { + executor.spin_some(std::chrono::milliseconds(100)); + rclcpp::sleep_for(std::chrono::milliseconds(100)); + } +} + +void updateNodeOptions( + rclcpp::NodeOptions & node_options, const std::vector & params_files) +{ + std::vector arguments; + arguments.push_back("--ros-args"); + arguments.push_back("--params-file"); + for (const auto & param_file : params_files) { + arguments.push_back(param_file.c_str()); + arguments.push_back("--params-file"); + } + arguments.pop_back(); + + node_options.arguments(std::vector{arguments.begin(), arguments.end()}); +} + +PathWithLaneId loadPathWithLaneIdInYaml() +{ + const auto planning_test_utils_dir = + ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto yaml_path = planning_test_utils_dir + "/config/path_with_lane_id_data.yaml"; + YAML::Node yaml_node = YAML::LoadFile(yaml_path); + PathWithLaneId path_msg; + + // Convert YAML data to PathWithLaneId message + // Fill the header + path_msg.header.stamp.sec = yaml_node["header"]["stamp"]["sec"].as(); + path_msg.header.stamp.nanosec = yaml_node["header"]["stamp"]["nanosec"].as(); + path_msg.header.frame_id = yaml_node["header"]["frame_id"].as(); + + // Fill the points + for (const auto & point_node : yaml_node["points"]) { + PathPointWithLaneId point; + // Fill the PathPoint data + point.point.pose.position.x = point_node["point"]["pose"]["position"]["x"].as(); + point.point.pose.position.y = point_node["point"]["pose"]["position"]["y"].as(); + point.point.pose.position.z = point_node["point"]["pose"]["position"]["z"].as(); + point.point.pose.orientation.x = point_node["point"]["pose"]["orientation"]["x"].as(); + point.point.pose.orientation.y = point_node["point"]["pose"]["orientation"]["y"].as(); + point.point.pose.orientation.z = point_node["point"]["pose"]["orientation"]["z"].as(); + point.point.pose.orientation.w = point_node["point"]["pose"]["orientation"]["w"].as(); + point.point.longitudinal_velocity_mps = + point_node["point"]["longitudinal_velocity_mps"].as(); + point.point.lateral_velocity_mps = point_node["point"]["lateral_velocity_mps"].as(); + point.point.heading_rate_rps = point_node["point"]["heading_rate_rps"].as(); + point.point.is_final = point_node["point"]["is_final"].as(); + // Fill the lane_ids + for (const auto & lane_id_node : point_node["lane_ids"]) { + point.lane_ids.push_back(lane_id_node.as()); + } + + path_msg.points.push_back(point); + } + + // Fill the left_bound + for (const auto & point_node : yaml_node["left_bound"]) { + Point point; + // Fill the Point data (left_bound) + point.x = point_node["x"].as(); + point.y = point_node["y"].as(); + point.z = point_node["z"].as(); + + path_msg.left_bound.push_back(point); + } + + // Fill the right_bound + for (const auto & point_node : yaml_node["right_bound"]) { + Point point; + // Fill the Point data + point.x = point_node["x"].as(); + point.y = point_node["y"].as(); + point.z = point_node["z"].as(); + + path_msg.right_bound.push_back(point); + } + return path_msg; +} + +} // namespace test_utils diff --git a/planning/planning_test_utils/test/test_mock_data_parser.cpp b/planning/planning_test_utils/test/test_mock_data_parser.cpp new file mode 100644 index 0000000000000..cda09522d8e6e --- /dev/null +++ b/planning/planning_test_utils/test/test_mock_data_parser.cpp @@ -0,0 +1,135 @@ +// Copyright 2024 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 + +// Assuming the parseRouteFile function is in 'RouteHandler.h' +#include "ament_index_cpp/get_package_share_directory.hpp" +#include "planning_test_utils/mock_data_parser.hpp" + +namespace test_utils +{ +// Example YAML structure as a string for testing +const char g_complete_yaml[] = R"( +start_pose: + position: + x: 1.0 + y: 2.0 + z: 3.0 + orientation: + x: 0.1 + y: 0.2 + z: 0.3 + w: 0.4 +goal_pose: + position: + x: 4.0 + y: 5.0 + z: 6.0 + orientation: + x: 0.5 + y: 0.6 + z: 0.7 + w: 0.8 +segments: +- preferred_primitive: + id: 11 + primitive_type: '' + primitives: + - id: 22 + primitive_type: lane + - id: 33 + primitive_type: lane +)"; + +TEST(ParseFunctions, CompleteYAMLTest) +{ + YAML::Node config = YAML::Load(g_complete_yaml); + + // Test parsing of start_pose and goal_pose + Pose start_pose = parse_pose(config["start_pose"]); + Pose goal_pose = parse_pose(config["goal_pose"]); + + EXPECT_DOUBLE_EQ(start_pose.position.x, 1.0); + EXPECT_DOUBLE_EQ(start_pose.position.y, 2.0); + EXPECT_DOUBLE_EQ(start_pose.position.z, 3.0); + + EXPECT_DOUBLE_EQ(start_pose.orientation.x, 0.1); + EXPECT_DOUBLE_EQ(start_pose.orientation.y, 0.2); + EXPECT_DOUBLE_EQ(start_pose.orientation.z, 0.3); + EXPECT_DOUBLE_EQ(start_pose.orientation.w, 0.4); + + EXPECT_DOUBLE_EQ(goal_pose.position.x, 4.0); + EXPECT_DOUBLE_EQ(goal_pose.position.y, 5.0); + EXPECT_DOUBLE_EQ(goal_pose.position.z, 6.0); + EXPECT_DOUBLE_EQ(goal_pose.orientation.x, 0.5); + EXPECT_DOUBLE_EQ(goal_pose.orientation.y, 0.6); + EXPECT_DOUBLE_EQ(goal_pose.orientation.z, 0.7); + EXPECT_DOUBLE_EQ(goal_pose.orientation.w, 0.8); + + // Test parsing of segments + std::vector segments = parse_segments(config["segments"]); + ASSERT_EQ( + segments.size(), uint64_t(1)); // Assuming only one segment in the provided YAML for this test + + const auto & segment0 = segments[0]; + EXPECT_EQ(segment0.preferred_primitive.id, 11); + EXPECT_EQ(segment0.primitives.size(), uint64_t(2)); + EXPECT_EQ(segment0.primitives[0].id, 22); + EXPECT_EQ(segment0.primitives[0].primitive_type, "lane"); + EXPECT_EQ(segment0.primitives[1].id, 33); + EXPECT_EQ(segment0.primitives[1].primitive_type, "lane"); +} + +TEST(ParseFunction, CompleteFromFilename) +{ + const auto planning_test_utils_dir = + ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto parser_test_route = + planning_test_utils_dir + "/test_data/lanelet_route_parser_test.yaml"; + + const auto lanelet_route = parse_lanelet_route_file(parser_test_route); + EXPECT_DOUBLE_EQ(lanelet_route.start_pose.position.x, 1.0); + EXPECT_DOUBLE_EQ(lanelet_route.start_pose.position.y, 2.0); + EXPECT_DOUBLE_EQ(lanelet_route.start_pose.position.z, 3.0); + + EXPECT_DOUBLE_EQ(lanelet_route.start_pose.orientation.x, 0.1); + EXPECT_DOUBLE_EQ(lanelet_route.start_pose.orientation.y, 0.2); + EXPECT_DOUBLE_EQ(lanelet_route.start_pose.orientation.z, 0.3); + EXPECT_DOUBLE_EQ(lanelet_route.start_pose.orientation.w, 0.4); + + EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.position.x, 4.0); + EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.position.y, 5.0); + EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.position.z, 6.0); + EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.orientation.x, 0.5); + EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.orientation.y, 0.6); + EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.orientation.z, 0.7); + EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.orientation.w, 0.8); + + ASSERT_EQ( + lanelet_route.segments.size(), + uint64_t(2)); // Assuming only one segment in the provided YAML for this test + const auto & segment1 = lanelet_route.segments[1]; + EXPECT_EQ(segment1.preferred_primitive.id, 44); + EXPECT_EQ(segment1.primitives.size(), uint64_t(4)); + EXPECT_EQ(segment1.primitives[0].id, 55); + EXPECT_EQ(segment1.primitives[0].primitive_type, "lane"); + EXPECT_EQ(segment1.primitives[1].id, 66); + EXPECT_EQ(segment1.primitives[1].primitive_type, "lane"); + EXPECT_EQ(segment1.primitives[2].id, 77); + EXPECT_EQ(segment1.primitives[2].primitive_type, "lane"); + EXPECT_EQ(segment1.primitives[3].id, 88); + EXPECT_EQ(segment1.primitives[3].primitive_type, "lane"); +} +} // namespace test_utils diff --git a/planning/planning_test_utils/test_data/lanelet_route_parser_test.yaml b/planning/planning_test_utils/test_data/lanelet_route_parser_test.yaml new file mode 100644 index 0000000000000..06ed15d20d3c9 --- /dev/null +++ b/planning/planning_test_utils/test_data/lanelet_route_parser_test.yaml @@ -0,0 +1,41 @@ +start_pose: + position: + x: 1.0 + y: 2.0 + z: 3.0 + orientation: + x: 0.1 + y: 0.2 + z: 0.3 + w: 0.4 +goal_pose: + position: + x: 4.0 + y: 5.0 + z: 6.0 + orientation: + x: 0.5 + y: 0.6 + z: 0.7 + w: 0.8 +segments: + - preferred_primitive: + id: 11 + primitive_type: "" + primitives: + - id: 22 + primitive_type: lane + - id: 33 + primitive_type: lane + - preferred_primitive: + id: 44 + primitive_type: "" + primitives: + - id: 55 + primitive_type: lane + - id: 66 + primitive_type: lane + - id: 77 + primitive_type: lane + - id: 88 + primitive_type: lane diff --git a/planning/planning_test_utils/test_map/2km_test.osm b/planning/planning_test_utils/test_map/2km_test.osm new file mode 100644 index 0000000000000..43c22f8de6bb1 --- /dev/null +++ b/planning/planning_test_utils/test_map/2km_test.osm @@ -0,0 +1,33390 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 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/route_handler/CMakeLists.txt b/planning/route_handler/CMakeLists.txt index 54b34f11f5363..414489e899fff 100644 --- a/planning/route_handler/CMakeLists.txt +++ b/planning/route_handler/CMakeLists.txt @@ -8,4 +8,16 @@ ament_auto_add_library(route_handler SHARED src/route_handler.cpp ) -ament_auto_package() +if(BUILD_TESTING) + ament_add_ros_isolated_gtest(test_route_handler + test/test_route_handler.cpp) + + target_link_libraries(test_route_handler + route_handler + ) + +endif() + +ament_auto_package(INSTALL_TO_SHARE + test_route +) diff --git a/planning/route_handler/README.md b/planning/route_handler/README.md index 4d369349bf364..e8df4fd087930 100644 --- a/planning/route_handler/README.md +++ b/planning/route_handler/README.md @@ -1,3 +1,18 @@ # route handler `route_handler` is a library for calculating driving route on the lanelet map. + +## Unit Testing + +The unit testing depends on `planning_test_utils` package. +`planning_test_utils` is a library that provides several common functions to simplify unit test creating. + +![route_handler_test](./images/route_handler_test.svg) + +By default, route file is necessary to create tests. The following illustrates the route that are used in the unit test + +### Lane change test route + +![lane_change_test_route](./images/lane_change_test_route.svg) + +- The route is based on map that can be obtained from `planning_test_utils\test_map` diff --git a/planning/route_handler/images/lane_change_test_route.svg b/planning/route_handler/images/lane_change_test_route.svg new file mode 100644 index 0000000000000..e71c8e13b1760 --- /dev/null +++ b/planning/route_handler/images/lane_change_test_route.svg @@ -0,0 +1,618 @@ + + + + + + + + + + + + + +
+
+
+ 4765 +
+
+
+
+ +
+
+
+ + + + + + + + + +
+
+
+ 25.0 meter +
+
+
+
+ +
+
+
+ + + + + + + +
+
+
+ 4770 +
+
+
+
+ +
+
+
+ + + + + + + +
+
+
+ 4775 +
+
+
+
+ +
+
+
+ + + + + + + +
+
+
+ 4424 +
+
+
+
+ +
+
+
+ + + + + + + +
+
+
+ 4780 +
+
+
+
+ +
+
+
+ + + + + + + +
+
+
+ 5088 +
+
+
+
+ +
+
+
+ + + + + + + +
+
+
+
goal pose
+ (70.0, -1.75) +
+
+
+
+ +
+
+
+ + + + + + + + + + + + + + +
+
+
+ 9590 +
+
+
+
+ +
+
+
+ + + + + + + +
+
+
+ 9594 +
+
+
+
+ +
+
+
+ + + + + + + +
+
+
+ 9598 +
+
+
+
+ +
+
+
+ + + + + + + +
+
+
+ 5072 +
+
+
+
+ +
+
+
+ + + + + + + +
+
+
+ 5084 +
+
+
+
+ +
+
+
+ + + + + + + +
+
+
+ 4765 +
+
+
+
+ +
+
+
+ + + + + + + + + +
+
+
+ 3.5 meter +
+
+
+
+ +
+
+
+ + + + +
+
+
+ preferred primitive +
+
+
+
+ +
+
+
+ + + + +
+
+
+ primitive +
+
+
+
+ +
+
+
+ + + + + + + +
+
+
+ pose1 +
+ (0.0, 1.75) +
+
+
+
+
+
+ +
+
+
+ + + + + + + + + + + + + + + + + + + + + +
+
+
+ check point +
+ (25.0, 1.75) +
+
+
+
+
+
+ +
+
+
+ + + + + + + +
+
+
+ start pose +
+ (-50.0, 1.75) +
+
+
+
+
+
+ +
+
+
+ + + + + + + + + + + + + +
+
diff --git a/planning/route_handler/images/route_handler_test.svg b/planning/route_handler/images/route_handler_test.svg new file mode 100644 index 0000000000000..38b2a97da0432 --- /dev/null +++ b/planning/route_handler/images/route_handler_test.svg @@ -0,0 +1,231 @@ + + + + + + + + + + + + + + + + + +
+
+
+ + route msg in yaml format +
+
+ (to simulate /planning/mission_planner/route topic) +
+
+
+
+ +
+
+
+ + + + + + + + + + + +
+
+
+ mock_data_parser +
+
+
+
+ +
+
+
+ + + + + + + +
+
+
+ LaneletRoute +
+
+
+
+ +
+
+
+ + + + + + + + + + + +
+
+
+ lanelet file +
+
+
+
+ +
+
+
+ + + + + + + + + + + +
+
+
+ HADMapBin +
+
+
+
+ +
+
+
+ + + + + + + + + + + +
+
+
+ test route handler +
+
+
+
+ +
+
+
+ + + + + + + + + + +
+
+
+ planning_test_utils +
+
+
+
+ +
+
+
+
+
diff --git a/planning/route_handler/include/route_handler/route_handler.hpp b/planning/route_handler/include/route_handler/route_handler.hpp index ac8e472b2f943..73bf99962ea82 100644 --- a/planning/route_handler/include/route_handler/route_handler.hpp +++ b/planning/route_handler/include/route_handler/route_handler.hpp @@ -27,6 +27,7 @@ #include #include #include +#include #include #include @@ -77,6 +78,7 @@ class RouteHandler lanelet::traffic_rules::TrafficRulesPtr getTrafficRulesPtr() const; std::shared_ptr getOverallGraphPtr() const; lanelet::LaneletMapPtr getLaneletMapPtr() const; + static bool isNoDrivableLane(const lanelet::ConstLanelet & llt); // for routing bool planPathLaneletsBetweenCheckpoints( @@ -203,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 @@ -274,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. @@ -319,14 +261,9 @@ 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; - lanelet::ConstLanelets getShoulderLanelets() const; bool isShoulderLanelet(const lanelet::ConstLanelet & lanelet) const; bool isRouteLanelet(const lanelet::ConstLanelet & lanelet) const; + bool isRoadLanelet(const lanelet::ConstLanelet & lanelet) const; lanelet::ConstLanelets getPreferredLanelets() const; // for path @@ -337,24 +274,16 @@ 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; - static bool getPullOverTarget( - const lanelet::ConstLanelets & lanelets, const Pose & goal_pose, - lanelet::ConstLanelet * target_lanelet); - static bool getPullOutStartLane( - const lanelet::ConstLanelets & lanelets, const Pose & pose, const double vehicle_width, - lanelet::ConstLanelet * target_lanelet); - double getLaneChangeableDistance(const Pose & current_pose, const Direction & direction) const; - bool getLeftShoulderLanelet( - const lanelet::ConstLanelet & lanelet, lanelet::ConstLanelet * left_lanelet) const; - bool getRightShoulderLanelet( - const lanelet::ConstLanelet & lanelet, lanelet::ConstLanelet * right_lanelet) const; + std::optional getPullOverTarget(const Pose & goal_pose) const; + std::optional getPullOutStartLane( + const Pose & pose, const double vehicle_width) const; + lanelet::ConstLanelets getRoadLaneletsAtPose(const Pose & pose) const; + std::optional getLeftShoulderLanelet( + const lanelet::ConstLanelet & lanelet) const; + std::optional getRightShoulderLanelet( + 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; - lanelet::ConstLanelets getClosestLanelets(const geometry_msgs::msg::Pose & target_pose) const; private: // MUST @@ -362,12 +291,10 @@ class RouteHandler lanelet::traffic_rules::TrafficRulesPtr traffic_rules_ptr_; std::shared_ptr overall_graphs_ptr_; lanelet::LaneletMapPtr lanelet_map_ptr_; - lanelet::ConstLanelets road_lanelets_; lanelet::ConstLanelets route_lanelets_; lanelet::ConstLanelets preferred_lanelets_; lanelet::ConstLanelets start_lanelets_; lanelet::ConstLanelets goal_lanelets_; - lanelet::ConstLanelets shoulder_lanelets_; std::shared_ptr route_ptr_{nullptr}; rclcpp::Logger logger_{rclcpp::get_logger("route_handler")}; @@ -387,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; @@ -409,30 +334,25 @@ class RouteHandler const lanelet::ConstLanelet & lanelet, const double min_length = std::numeric_limits::max(), const bool only_route_lanes = true) const; - bool getFollowingShoulderLanelet( - const lanelet::ConstLanelet & lanelet, lanelet::ConstLanelet * following_lanelet) const; + std::optional getFollowingShoulderLanelet( + const lanelet::ConstLanelet & lanelet) const; lanelet::ConstLanelets getShoulderLaneletSequenceAfter( const lanelet::ConstLanelet & lanelet, const double min_length = std::numeric_limits::max()) const; - bool getPreviousShoulderLanelet( - const lanelet::ConstLanelet & lanelet, lanelet::ConstLanelet * prev_lanelet) const; + std::optional getPreviousShoulderLanelet( + const lanelet::ConstLanelet & lanelet) const; lanelet::ConstLanelets getShoulderLaneletSequenceUpTo( const lanelet::ConstLanelet & lanelet, const double min_length = std::numeric_limits::max()) const; lanelet::ConstLanelets getPreviousLaneletSequence( const lanelet::ConstLanelets & lanelet_sequence) const; - lanelet::ConstLanelets getClosestLaneletSequence(const Pose & pose) 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 @@ -441,17 +361,41 @@ class RouteHandler */ bool hasNoDrivableLaneInPath(const lanelet::routing::LaneletPath & path) const; /** - * @brief Searches for a path between start and goal lanelets that does not include any - * no_drivable_lane. If there is more than one path fount, the function returns the shortest path - * that does not include any no_drivable_lane. + * @brief Searches for the shortest path between start and goal lanelets that does not include any + * no_drivable_lane. * @param start_lanelet start lanelet * @param goal_lanelet goal lanelet - * @param drivable_lane_path output path that does not include no_drivable_lane. - * @return true if a path without any no_drivable_lane found, false if this path is not found. + * @return the lanelet path (if found) */ - bool findDrivableLanePath( - const lanelet::ConstLanelet & start_lanelet, const lanelet::ConstLanelet & goal_lanelet, - lanelet::routing::LaneletPath & drivable_lane_path) const; + std::optional findDrivableLanePath( + const lanelet::ConstLanelet & start_lanelet, const lanelet::ConstLanelet & goal_lanelet) const; }; + +/// @brief custom routing cost with infinity cost for no drivable lanes +class RoutingCostDrivable : public lanelet::routing::RoutingCostDistance +{ +public: + RoutingCostDrivable() : lanelet::routing::RoutingCostDistance(10.0) {} + inline double getCostSucceeding( + const lanelet::traffic_rules::TrafficRules & trafficRules, + const lanelet::ConstLaneletOrArea & from, const lanelet::ConstLaneletOrArea & to) const + { + if ( + (from.isLanelet() && RouteHandler::isNoDrivableLane(*from.lanelet())) || + (to.isLanelet() && RouteHandler::isNoDrivableLane(*to.lanelet()))) + return std::numeric_limits::infinity(); + return lanelet::routing::RoutingCostDistance::getCostSucceeding(trafficRules, from, to); + } + inline double getCostLaneChange( + const lanelet::traffic_rules::TrafficRules & trafficRules, const lanelet::ConstLanelets & from, + const lanelet::ConstLanelets & to) const noexcept + { + if ( + std::any_of(from.begin(), from.end(), RouteHandler::isNoDrivableLane) || + std::any_of(to.begin(), to.end(), RouteHandler::isNoDrivableLane)) + return std::numeric_limits::infinity(); + return lanelet::routing::RoutingCostDistance::getCostLaneChange(trafficRules, from, to); + } +}; // class RoutingCostDrivable } // namespace route_handler #endif // ROUTE_HANDLER__ROUTE_HANDLER_HPP_ diff --git a/planning/route_handler/package.xml b/planning/route_handler/package.xml index 60adfb1531104..097bc62f8bf39 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 @@ -16,6 +18,7 @@ ament_cmake_auto autoware_cmake + ament_cmake_ros ament_lint_auto autoware_lint_common @@ -24,10 +27,12 @@ autoware_planning_msgs geometry_msgs lanelet2_extension + planning_test_utils rclcpp rclcpp_components tf2_ros tier4_autoware_utils + yaml-cpp ament_cmake diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index 76763821998bd..4dd559b9bbc98 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -157,8 +157,6 @@ void RouteHandler::setMap(const HADMapBin & map_msg) overall_graphs_ptr_ = std::make_shared(overall_graphs); lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_ptr_); - road_lanelets_ = lanelet::utils::query::roadLanelets(all_lanelets); - shoulder_lanelets_ = lanelet::utils::query::shoulderLanelets(all_lanelets); is_map_msg_ready_ = true; is_handler_ready_ = false; @@ -575,44 +573,26 @@ lanelet::ConstLanelets RouteHandler::getLaneletSequenceUpTo( lanelet::ConstLanelet current_lanelet = lanelet; double length = 0; + lanelet::ConstLanelets previous_lanelets; while (rclcpp::ok() && length < min_length) { - lanelet::ConstLanelets candidate_lanelets; - if (!getPreviousLaneletsWithinRoute(current_lanelet, &candidate_lanelets)) { - if (only_route_lanes) { - break; - } - const auto prev_lanes = getPreviousLanelets(current_lanelet); - if (prev_lanes.empty()) { - break; - } - candidate_lanelets = prev_lanes; + previous_lanelets.clear(); + if (!getPreviousLaneletsWithinRoute(current_lanelet, &previous_lanelets)) { + if (only_route_lanes) break; + const auto previous_lanelets = getPreviousLanelets(current_lanelet); + if (previous_lanelets.empty()) break; } // loop check - if (std::any_of( - candidate_lanelets.begin(), candidate_lanelets.end(), - [lanelet](auto & prev_llt) { return lanelet.id() == prev_llt.id(); })) { + if (std::any_of(previous_lanelets.begin(), previous_lanelets.end(), [lanelet](auto & prev_llt) { + return lanelet.id() == prev_llt.id(); + })) { break; } - // If lanelet_sequence_backward with input lanelet contains all candidate lanelets, - // break the loop. - if (std::all_of( - candidate_lanelets.begin(), candidate_lanelets.end(), - [lanelet_sequence_backward, lanelet](auto & prev_llt) { - return std::any_of( - lanelet_sequence_backward.begin(), lanelet_sequence_backward.end(), - [prev_llt, lanelet](auto & llt) { - return (llt.id() == prev_llt.id() || lanelet.id() == prev_llt.id()); - }); - })) { - break; - } - - for (const auto & prev_lanelet : candidate_lanelets) { + for (const auto & prev_lanelet : previous_lanelets) { if (std::any_of( lanelet_sequence_backward.begin(), lanelet_sequence_backward.end(), - [prev_lanelet, lanelet](auto & llt) { - return (llt.id() == prev_lanelet.id() || lanelet.id() == prev_lanelet.id()); + [prev_lanelet, lanelet](auto & backward) { + return (backward.id() == prev_lanelet.id()); })) { continue; } @@ -646,7 +626,7 @@ lanelet::ConstLanelets RouteHandler::getLaneletSequence( const lanelet::ConstLanelets lanelet_sequence_forward = std::invoke([&]() { if (only_route_lanes) { return getLaneletSequenceAfter(lanelet, forward_distance, only_route_lanes); - } else if (lanelet::utils::contains(shoulder_lanelets_, lanelet)) { + } else if (isShoulderLanelet(lanelet)) { return getShoulderLaneletSequenceAfter(lanelet, forward_distance); } return lanelet::ConstLanelets{}; @@ -656,7 +636,7 @@ lanelet::ConstLanelets RouteHandler::getLaneletSequence( if (arc_coordinate.length < backward_distance) { if (only_route_lanes) { return getLaneletSequenceUpTo(lanelet, backward_distance, only_route_lanes); - } else if (lanelet::utils::contains(shoulder_lanelets_, lanelet)) { + } else if (isShoulderLanelet(lanelet)) { return getShoulderLaneletSequenceUpTo(lanelet, backward_distance); } } @@ -682,14 +662,13 @@ lanelet::ConstLanelets RouteHandler::getLaneletSequence( const lanelet::ConstLanelet & lanelet, const Pose & current_pose, const double backward_distance, const double forward_distance, const bool only_route_lanes) const { - lanelet::ConstLanelets lanelet_sequence; if (only_route_lanes && !exists(route_lanelets_, lanelet)) { - return lanelet_sequence; + return {}; } lanelet::ConstLanelets lanelet_sequence_forward = getLaneletSequenceAfter(lanelet, forward_distance, only_route_lanes); - const lanelet::ConstLanelets lanelet_sequence_backward = std::invoke([&]() { + lanelet::ConstLanelets lanelet_sequence = std::invoke([&]() { const auto arc_coordinate = lanelet::utils::getArcCoordinates({lanelet}, current_pose); if (arc_coordinate.length < backward_distance) { return getLaneletSequenceUpTo(lanelet, backward_distance, only_route_lanes); @@ -698,124 +677,148 @@ lanelet::ConstLanelets RouteHandler::getLaneletSequence( }); // loop check - if (!lanelet_sequence_forward.empty() && !lanelet_sequence_backward.empty()) { - if (lanelet_sequence_backward.back().id() == lanelet_sequence_forward.front().id()) { + if (!lanelet_sequence_forward.empty() && !lanelet_sequence.empty()) { + if (lanelet_sequence.back().id() == lanelet_sequence_forward.front().id()) { return lanelet_sequence_forward; } } - lanelet_sequence.insert( - lanelet_sequence.end(), lanelet_sequence_backward.begin(), lanelet_sequence_backward.end()); lanelet_sequence.push_back(lanelet); - lanelet_sequence.insert( - lanelet_sequence.end(), lanelet_sequence_forward.begin(), lanelet_sequence_forward.end()); - + std::move( + lanelet_sequence_forward.begin(), lanelet_sequence_forward.end(), + std::back_inserter(lanelet_sequence)); return lanelet_sequence; } -bool RouteHandler::getFollowingShoulderLanelet( - const lanelet::ConstLanelet & lanelet, lanelet::ConstLanelet * following_lanelet) const +lanelet::ConstLanelets RouteHandler::getRoadLaneletsAtPose(const Pose & pose) const { - for (const auto & shoulder_lanelet : shoulder_lanelets_) { - if (lanelet::geometry::follows(lanelet, shoulder_lanelet)) { - *following_lanelet = shoulder_lanelet; - return true; - } + lanelet::ConstLanelets road_lanelets_at_pose; + const lanelet::BasicPoint2d p{pose.position.x, pose.position.y}; + const auto lanelets_at_pose = lanelet_map_ptr_->laneletLayer.search(lanelet::BoundingBox2d(p)); + for (const auto & lanelet_at_pose : lanelets_at_pose) { + // confirm that the pose is inside the lanelet since "search" does an approximation with boxes + const auto is_pose_inside_lanelet = lanelet::geometry::inside(lanelet_at_pose, p); + if (is_pose_inside_lanelet && isRoadLanelet(lanelet_at_pose)) + road_lanelets_at_pose.push_back(lanelet_at_pose); } - return false; + return road_lanelets_at_pose; } -bool RouteHandler::getLeftShoulderLanelet( - const lanelet::ConstLanelet & lanelet, lanelet::ConstLanelet * left_lanelet) const +std::optional RouteHandler::getFollowingShoulderLanelet( + const lanelet::ConstLanelet & lanelet) const { - for (const auto & shoulder_lanelet : shoulder_lanelets_) { - if (lanelet::geometry::leftOf(shoulder_lanelet, lanelet)) { - *left_lanelet = shoulder_lanelet; - return true; - } + bool found = false; + const auto & search_point = lanelet.centerline().back().basicPoint2d(); + const auto next_lanelet = lanelet_map_ptr_->laneletLayer.nearestUntil( + search_point, [&](const auto & bbox, const auto & ll) { + if (isShoulderLanelet(ll) && lanelet::geometry::follows(lanelet, ll)) found = true; + // stop search once next shoulder lanelet is found, or the bbox does not touch the search + // point + return found || lanelet::geometry::distance2d(bbox, search_point) > 1e-3; + }); + if (found && next_lanelet.has_value()) return *next_lanelet; + return std::nullopt; +} + +std::optional RouteHandler::getLeftShoulderLanelet( + const lanelet::ConstLanelet & lanelet) const +{ + for (const auto & other_lanelet : + lanelet_map_ptr_->laneletLayer.findUsages(lanelet.leftBound())) { + if (other_lanelet.rightBound() == lanelet.leftBound() && isShoulderLanelet(other_lanelet)) + return other_lanelet; } - return false; + return std::nullopt; } -bool RouteHandler::getRightShoulderLanelet( - const lanelet::ConstLanelet & lanelet, lanelet::ConstLanelet * right_lanelet) const +std::optional RouteHandler::getRightShoulderLanelet( + const lanelet::ConstLanelet & lanelet) const { - for (const auto & shoulder_lanelet : shoulder_lanelets_) { - if (lanelet::geometry::rightOf(shoulder_lanelet, lanelet)) { - *right_lanelet = shoulder_lanelet; - return true; - } + for (const auto & other_lanelet : + lanelet_map_ptr_->laneletLayer.findUsages(lanelet.rightBound())) { + if (other_lanelet.leftBound() == lanelet.rightBound() && isShoulderLanelet(other_lanelet)) + return other_lanelet; } - return false; + return std::nullopt; +} + +lanelet::ConstLanelets RouteHandler::getShoulderLaneletsAtPose(const Pose & pose) const +{ + lanelet::ConstLanelets lanelets_at_pose; + const lanelet::BasicPoint2d p{pose.position.x, pose.position.y}; + const auto candidates_at_pose = lanelet_map_ptr_->laneletLayer.search(lanelet::BoundingBox2d(p)); + for (const auto & candidate : candidates_at_pose) { + // confirm that the pose is inside the lanelet since "search" does an approximation with boxes + const auto is_pose_inside_lanelet = lanelet::geometry::inside(candidate, p); + if (is_pose_inside_lanelet && isShoulderLanelet(candidate)) + lanelets_at_pose.push_back(candidate); + } + return lanelets_at_pose; } lanelet::ConstLanelets RouteHandler::getShoulderLaneletSequenceAfter( const lanelet::ConstLanelet & lanelet, const double min_length) const { lanelet::ConstLanelets lanelet_sequence_forward; - if (!exists(shoulder_lanelets_, lanelet)) { - return lanelet_sequence_forward; - } + if (!isShoulderLanelet(lanelet)) return lanelet_sequence_forward; double length = 0; lanelet::ConstLanelet current_lanelet = lanelet; std::set searched_ids{}; while (rclcpp::ok() && length < min_length) { - lanelet::ConstLanelet next_lanelet; - if (!getFollowingShoulderLanelet(current_lanelet, &next_lanelet)) { - break; - } - lanelet_sequence_forward.push_back(next_lanelet); - if (searched_ids.find(next_lanelet.id()) != searched_ids.end()) { + const auto next_lanelet = getFollowingShoulderLanelet(current_lanelet); + if (!next_lanelet) break; + lanelet_sequence_forward.push_back(*next_lanelet); + if (searched_ids.find(next_lanelet->id()) != searched_ids.end()) { // loop shoulder detected break; } - searched_ids.insert(next_lanelet.id()); - current_lanelet = next_lanelet; + searched_ids.insert(next_lanelet->id()); + current_lanelet = *next_lanelet; length += - static_cast(boost::geometry::length(next_lanelet.centerline().basicLineString())); + static_cast(boost::geometry::length(next_lanelet->centerline().basicLineString())); } return lanelet_sequence_forward; } -bool RouteHandler::getPreviousShoulderLanelet( - const lanelet::ConstLanelet & lanelet, lanelet::ConstLanelet * prev_lanelet) const +std::optional RouteHandler::getPreviousShoulderLanelet( + const lanelet::ConstLanelet & lanelet) const { - for (const auto & shoulder_lanelet : shoulder_lanelets_) { - if (lanelet::geometry::follows(shoulder_lanelet, lanelet)) { - *prev_lanelet = shoulder_lanelet; - return true; - } - } - return false; + bool found = false; + const auto & search_point = lanelet.centerline().front().basicPoint2d(); + const auto previous_lanelet = lanelet_map_ptr_->laneletLayer.nearestUntil( + search_point, [&](const auto & bbox, const auto & ll) { + if (isShoulderLanelet(ll) && lanelet::geometry::follows(ll, lanelet)) found = true; + // stop search once prev shoulder lanelet is found, or the bbox does not touch the search + // point + return found || lanelet::geometry::distance2d(bbox, search_point) > 1e-3; + }); + if (found && previous_lanelet.has_value()) return *previous_lanelet; + return std::nullopt; } lanelet::ConstLanelets RouteHandler::getShoulderLaneletSequenceUpTo( const lanelet::ConstLanelet & lanelet, const double min_length) const { lanelet::ConstLanelets lanelet_sequence_backward; - if (!exists(shoulder_lanelets_, lanelet)) { - return lanelet_sequence_backward; - } + if (!isShoulderLanelet(lanelet)) return lanelet_sequence_backward; double length = 0; lanelet::ConstLanelet current_lanelet = lanelet; std::set searched_ids{}; while (rclcpp::ok() && length < min_length) { - lanelet::ConstLanelet prev_lanelet; - if (!getPreviousShoulderLanelet(current_lanelet, &prev_lanelet)) { - break; - } + const auto prev_lanelet = getPreviousShoulderLanelet(current_lanelet); + if (!prev_lanelet) break; - lanelet_sequence_backward.insert(lanelet_sequence_backward.begin(), prev_lanelet); - if (searched_ids.find(prev_lanelet.id()) != searched_ids.end()) { + lanelet_sequence_backward.insert(lanelet_sequence_backward.begin(), *prev_lanelet); + if (searched_ids.find(prev_lanelet->id()) != searched_ids.end()) { // loop shoulder detected break; } - searched_ids.insert(prev_lanelet.id()); - current_lanelet = prev_lanelet; + searched_ids.insert(prev_lanelet->id()); + current_lanelet = *prev_lanelet; length += - static_cast(boost::geometry::length(prev_lanelet.centerline().basicLineString())); + static_cast(boost::geometry::length(prev_lanelet->centerline().basicLineString())); } return lanelet_sequence_backward; @@ -826,7 +829,7 @@ lanelet::ConstLanelets RouteHandler::getShoulderLaneletSequence( const double forward_distance) const { lanelet::ConstLanelets lanelet_sequence; - if (!exists(shoulder_lanelets_, lanelet)) { + if (!isShoulderLanelet(lanelet)) { return lanelet_sequence; } @@ -1009,20 +1012,16 @@ std::optional RouteHandler::getRightLanelet( { // right road lanelet of shoulder lanelet if (isShoulderLanelet(lanelet)) { - for (const auto & road_lanelet : road_lanelets_) { - if (lanelet::geometry::rightOf(road_lanelet, lanelet)) { - return road_lanelet; - } - } + const auto right_lanelets = lanelet_map_ptr_->laneletLayer.findUsages(lanelet.rightBound()); + for (const auto & right_lanelet : right_lanelets) + if (isRoadLanelet(right_lanelet)) return right_lanelet; return std::nullopt; } // right shoulder lanelet if (get_shoulder_lane) { - lanelet::ConstLanelet right_shoulder_lanelet; - if (getRightShoulderLanelet(lanelet, &right_shoulder_lanelet)) { - return right_shoulder_lanelet; - } + const auto right_shoulder_lanelet = getRightShoulderLanelet(lanelet); + if (right_shoulder_lanelet) return *right_shoulder_lanelet; } // routable lane @@ -1090,20 +1089,16 @@ std::optional RouteHandler::getLeftLanelet( { // left road lanelet of shoulder lanelet if (isShoulderLanelet(lanelet)) { - for (const auto & road_lanelet : road_lanelets_) { - if (lanelet::geometry::leftOf(road_lanelet, lanelet)) { - return road_lanelet; - } - } + const auto left_lanelets = lanelet_map_ptr_->laneletLayer.findUsages(lanelet.leftBound()); + for (const auto & left_lanelet : left_lanelets) + if (isRoadLanelet(left_lanelet)) return left_lanelet; return std::nullopt; } // left shoulder lanelet if (get_shoulder_lane) { - lanelet::ConstLanelet left_shoulder_lanelet; - if (getLeftShoulderLanelet(lanelet, &left_shoulder_lanelet)) { - return left_shoulder_lanelet; - } + const auto left_shoulder_lanelet = getLeftShoulderLanelet(lanelet); + if (left_shoulder_lanelet) return *left_shoulder_lanelet; } // routable lane @@ -1308,98 +1303,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 @@ -1470,79 +1373,33 @@ 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; -} - -bool RouteHandler::getPullOverTarget( - const lanelet::ConstLanelets & lanelets, const Pose & goal_pose, - lanelet::ConstLanelet * target_lanelet) +std::optional RouteHandler::getPullOverTarget(const Pose & goal_pose) const { - for (const auto & shoulder_lanelet : lanelets) { - if (lanelet::utils::isInLanelet(goal_pose, shoulder_lanelet, 0.1)) { - *target_lanelet = shoulder_lanelet; - return true; - } + const lanelet::BasicPoint2d p(goal_pose.position.x, goal_pose.position.y); + constexpr auto search_distance = 0.1; + const lanelet::BasicPoint2d offset(search_distance, search_distance); + const auto lanelets_in_range = + lanelet_map_ptr_->laneletLayer.search(lanelet::BoundingBox2d(p - offset, p + offset)); + for (const auto & lanelet : lanelets_in_range) { + const auto is_in_lanelet = lanelet::utils::isInLanelet(goal_pose, lanelet, search_distance); + if (is_in_lanelet && isShoulderLanelet(lanelet)) return lanelet; } - return false; + return std::nullopt; } -bool RouteHandler::getPullOutStartLane( - const lanelet::ConstLanelets & lanelets, const Pose & pose, const double vehicle_width, - lanelet::ConstLanelet * target_lanelet) +std::optional RouteHandler::getPullOutStartLane( + const Pose & pose, const double vehicle_width) const { - for (const auto & shoulder_lanelet : lanelets) { - if (lanelet::utils::isInLanelet(pose, shoulder_lanelet, vehicle_width / 2.0)) { - *target_lanelet = shoulder_lanelet; - return true; - } + const lanelet::BasicPoint2d p(pose.position.x, pose.position.y); + const auto search_distance = vehicle_width / 2.0; + const lanelet::BasicPoint2d offset(search_distance, search_distance); + const auto lanelets_in_range = + lanelet_map_ptr_->laneletLayer.search(lanelet::BoundingBox2d(p - offset, p + offset)); + for (const auto & lanelet : lanelets_in_range) { + const auto is_in_lanelet = lanelet::utils::isInLanelet(pose, lanelet, search_distance); + if (is_in_lanelet && isShoulderLanelet(lanelet)) return lanelet; } - return false; -} - -lanelet::ConstLanelets RouteHandler::getClosestLaneletSequence(const Pose & pose) const -{ - lanelet::ConstLanelet lanelet; - if (!getClosestLaneletWithinRoute(pose, &lanelet)) { - return lanelet::ConstLanelets{}; - } - return getLaneletSequence(lanelet); + return std::nullopt; } int RouteHandler::getNumLaneToPreferredLane( @@ -1579,13 +1436,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 { @@ -1640,30 +1490,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 @@ -1739,139 +1565,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_; @@ -1898,49 +1591,10 @@ 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; -} - -lanelet::ConstLanelets RouteHandler::getShoulderLanelets() const -{ - return shoulder_lanelets_; -} - bool RouteHandler::isShoulderLanelet(const lanelet::ConstLanelet & lanelet) const { - return lanelet::utils::contains(shoulder_lanelets_, lanelet); + return lanelet.hasAttribute(lanelet::AttributeName::Subtype) && + lanelet.attribute(lanelet::AttributeName::Subtype) == "road_shoulder"; } bool RouteHandler::isRouteLanelet(const lanelet::ConstLanelet & lanelet) const @@ -1948,6 +1602,12 @@ bool RouteHandler::isRouteLanelet(const lanelet::ConstLanelet & lanelet) const return lanelet::utils::contains(route_lanelets_, lanelet); } +bool RouteHandler::isRoadLanelet(const lanelet::ConstLanelet & lanelet) const +{ + return lanelet.hasAttribute(lanelet::AttributeName::Subtype) && + lanelet.attribute(lanelet::AttributeName::Subtype) == lanelet::AttributeValueString::Road; +} + lanelet::ConstLanelets RouteHandler::getPreviousLaneletSequence( const lanelet::ConstLanelets & lanelet_sequence) const { @@ -2000,8 +1660,9 @@ lanelet::ConstLanelets RouteHandler::getLaneSequenceUpTo( } lanelet::ConstLanelet current_lanelet = lanelet; + lanelet::ConstLanelets candidate_lanelets; while (rclcpp::ok()) { - lanelet::ConstLanelets candidate_lanelets; + candidate_lanelets.clear(); if (!getPreviousLaneletsWithinRoute(current_lanelet, &candidate_lanelets)) { break; } @@ -2088,60 +1749,52 @@ 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 { // Find lanelets for start point. First, find all lanelets containing the start point to calculate - // all possible route later. It fails when the point is not located on any road_lanelet (e.g. the + // all possible route later. It fails when the point is not located on any road lanelet (e.g. the // start point is located out of any lanelets or road_shoulder lanelet which is not contained in - // road_lanelet). In that case, find the closest lanelet instead. + // road lanelet). In that case, find the closest lanelet instead (within some maximum range). + constexpr auto max_search_range = 20.0; + auto start_lanelets = getRoadLaneletsAtPose(start_checkpoint); lanelet::ConstLanelet start_lanelet; - lanelet::ConstLanelets start_lanelets; - if (!lanelet::utils::query::getCurrentLanelets( - road_lanelets_, start_checkpoint, &start_lanelets)) { - if (!lanelet::utils::query::getClosestLanelet( - road_lanelets_, start_checkpoint, &start_lanelet)) { - RCLCPP_WARN_STREAM( - logger_, "Failed to find current lanelet." - << std::endl - << " - start checkpoint: " << toString(start_checkpoint) << std::endl - << " - goal checkpoint: " << toString(goal_checkpoint) << std::endl); - return false; - } - start_lanelets = {start_lanelet}; + if (start_lanelets.empty()) { + const lanelet::BasicPoint2d p(start_checkpoint.position.x, start_checkpoint.position.y); + const lanelet::BoundingBox2d bbox( + lanelet::BasicPoint2d(p.x() - max_search_range, p.y() - max_search_range), + lanelet::BasicPoint2d(p.x() + max_search_range, p.y() + max_search_range)); + // std::as_const(*ptr) to use the const version of the search function + auto candidates = std::as_const(*lanelet_map_ptr_).laneletLayer.search(bbox); + candidates.erase( + std::remove_if( + candidates.begin(), candidates.end(), [&](const auto & l) { return !isRoadLanelet(l); }), + candidates.end()); + if (lanelet::utils::query::getClosestLanelet(candidates, start_checkpoint, &start_lanelet)) + start_lanelets = {start_lanelet}; + } + if (start_lanelets.empty()) { + RCLCPP_WARN_STREAM( + logger_, "Failed to find current lanelet." + << std::endl + << " - start checkpoint: " << toString(start_checkpoint) << std::endl + << " - goal checkpoint: " << toString(goal_checkpoint) << std::endl); + return false; } // Find lanelets for goal point. lanelet::ConstLanelet goal_lanelet; - if (!lanelet::utils::query::getClosestLanelet(road_lanelets_, goal_checkpoint, &goal_lanelet)) { + const lanelet::BasicPoint2d p(goal_checkpoint.position.x, goal_checkpoint.position.y); + const lanelet::BoundingBox2d bbox( + lanelet::BasicPoint2d(p.x() - max_search_range, p.y() - max_search_range), + lanelet::BasicPoint2d(p.x() + max_search_range, p.y() + max_search_range)); + auto candidates = std::as_const(*lanelet_map_ptr_).laneletLayer.search(bbox); + candidates.erase( + std::remove_if( + candidates.begin(), candidates.end(), [&](const auto & l) { return !isRoadLanelet(l); }), + candidates.end()); + if (!lanelet::utils::query::getClosestLanelet(candidates, goal_checkpoint, &goal_lanelet)) { RCLCPP_WARN_STREAM( logger_, "Failed to find closest lanelet." << std::endl @@ -2189,14 +1842,11 @@ bool RouteHandler::planPathLaneletsBetweenCheckpoints( if (is_route_found) { lanelet::routing::LaneletPath path; path = [&]() -> lanelet::routing::LaneletPath { - if (!consider_no_drivable_lanes) return shortest_path; - lanelet::routing::LaneletPath drivable_lane_path; - bool drivable_lane_path_found = false; - if (hasNoDrivableLaneInPath(shortest_path)) { - drivable_lane_path_found = - findDrivableLanePath(start_lanelet, goal_lanelet, drivable_lane_path); + if (consider_no_drivable_lanes && hasNoDrivableLaneInPath(shortest_path)) { + const auto drivable_lane_path = findDrivableLanePath(start_lanelet, goal_lanelet); + if (drivable_lane_path) return *drivable_lane_path; } - return (drivable_lane_path_found) ? drivable_lane_path : shortest_path; + return shortest_path; }(); path_lanelets->reserve(path.size()); @@ -2248,49 +1898,28 @@ lanelet::ConstLanelets RouteHandler::getMainLanelets( return main_lanelets; } -bool RouteHandler::hasNoDrivableLaneInPath(const lanelet::routing::LaneletPath & path) const +bool RouteHandler::isNoDrivableLane(const lanelet::ConstLanelet & llt) { - for (const auto & llt : path) { - const std::string no_drivable_lane_attribute = llt.attributeOr("no_drivable_lane", "no"); - if (no_drivable_lane_attribute == "yes") { - return true; - } - } - - return false; + const std::string no_drivable_lane_attribute = llt.attributeOr("no_drivable_lane", "no"); + return no_drivable_lane_attribute == "yes"; } -bool RouteHandler::findDrivableLanePath( - const lanelet::ConstLanelet & start_lanelet, const lanelet::ConstLanelet & goal_lanelet, - lanelet::routing::LaneletPath & drivable_lane_path) const +bool RouteHandler::hasNoDrivableLaneInPath(const lanelet::routing::LaneletPath & path) const { - double drivable_lane_path_length2d = std::numeric_limits::max(); - bool drivable_lane_path_found = false; - - for (const auto & llt : road_lanelets_) { - lanelet::ConstLanelets via_lanelet; - via_lanelet.push_back(llt); - const lanelet::Optional optional_route = - routing_graph_ptr_->getRouteVia(start_lanelet, via_lanelet, goal_lanelet, 0); - - if ((optional_route) && (!hasNoDrivableLaneInPath(optional_route->shortestPath()))) { - if (optional_route->length2d() < drivable_lane_path_length2d) { - drivable_lane_path_length2d = optional_route->length2d(); - drivable_lane_path = optional_route->shortestPath(); - drivable_lane_path_found = true; - } - } - via_lanelet.clear(); - } - - return drivable_lane_path_found; + for (const auto & llt : path) + if (isNoDrivableLane(llt)) return true; + return false; } -lanelet::ConstLanelets RouteHandler::getClosestLanelets( - const geometry_msgs::msg::Pose & target_pose) const +std::optional RouteHandler::findDrivableLanePath( + const lanelet::ConstLanelet & start_lanelet, const lanelet::ConstLanelet & goal_lanelet) const { - lanelet::ConstLanelets target_lanelets; - lanelet::utils::query::getCurrentLanelets(road_lanelets_, target_pose, &target_lanelets); - return target_lanelets; + // we create a new routing graph with infinite cost on no drivable lanes + const auto drivable_routing_graph_ptr = lanelet::routing::RoutingGraph::build( + *lanelet_map_ptr_, *traffic_rules_ptr_, + lanelet::routing::RoutingCostPtrs{std::make_shared()}); + const auto route = drivable_routing_graph_ptr->getRoute(start_lanelet, goal_lanelet, 0); + if (route) return route->shortestPath(); + return {}; } } // namespace route_handler diff --git a/planning/route_handler/test/test_route_handler.cpp b/planning/route_handler/test/test_route_handler.cpp new file mode 100644 index 0000000000000..212fc0ce84d89 --- /dev/null +++ b/planning/route_handler/test/test_route_handler.cpp @@ -0,0 +1,110 @@ +// Copyright 2024 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 "test_route_handler.hpp" + +#include + +#include + +namespace route_handler::test +{ +TEST_F(TestRouteHandler, isRouteHandlerReadyTest) +{ + ASSERT_TRUE(route_handler_->isHandlerReady()); +} + +TEST_F(TestRouteHandler, checkIfIDReturned) +{ + const auto lanelet1 = route_handler_->getLaneletsFromId(4785); + const auto is_lanelet1_in_goal_route_section = route_handler_->isInGoalRouteSection(lanelet1); + ASSERT_TRUE(is_lanelet1_in_goal_route_section); + + const auto lanelet2 = route_handler_->getLaneletsFromId(4780); + const auto is_lanelet2_in_goal_route_section = route_handler_->isInGoalRouteSection(lanelet2); + ASSERT_FALSE(is_lanelet2_in_goal_route_section); +} + +TEST_F(TestRouteHandler, getGoalLaneId) +{ + lanelet::ConstLanelet goal_lane; + + const auto goal_lane_obtained = route_handler_->getGoalLanelet(&goal_lane); + ASSERT_TRUE(goal_lane_obtained); + ASSERT_EQ(goal_lane.id(), 5088); +} + +// TEST_F(TestRouteHandler, getClosestLaneletWithinRouteWhenPointsInRoute) +// { +// lanelet::ConstLanelet closest_lane; + +// Pose search_pose; + +// search_pose.position = tier4_autoware_utils::createPoint(-1.0, 1.75, 0); +// search_pose.orientation = tier4_autoware_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); +// const auto closest_lane_obtained7 = +// route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane); + +// ASSERT_TRUE(closest_lane_obtained7); +// ASSERT_EQ(closest_lane.id(), 4775); + +// search_pose.position = tier4_autoware_utils::createPoint(-0.5, 1.75, 0); +// const auto closest_lane_obtained = +// search_pose.orientation = tier4_autoware_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); +// route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane); + +// ASSERT_TRUE(closest_lane_obtained); +// ASSERT_EQ(closest_lane.id(), 4775); + +// search_pose.position = tier4_autoware_utils::createPoint(-.01, 1.75, 0); +// search_pose.orientation = tier4_autoware_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); +// const auto closest_lane_obtained3 = +// route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane); + +// ASSERT_TRUE(closest_lane_obtained3); +// ASSERT_EQ(closest_lane.id(), 4775); + +// search_pose.position = tier4_autoware_utils::createPoint(0.0, 1.75, 0); +// search_pose.orientation = tier4_autoware_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); +// const auto closest_lane_obtained1 = +// route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane); + +// ASSERT_TRUE(closest_lane_obtained1); +// ASSERT_EQ(closest_lane.id(), 4775); + +// search_pose.position = tier4_autoware_utils::createPoint(0.01, 1.75, 0); +// search_pose.orientation = tier4_autoware_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); +// const auto closest_lane_obtained2 = +// route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane); + +// ASSERT_TRUE(closest_lane_obtained2); +// ASSERT_EQ(closest_lane.id(), 4424); + +// search_pose.position = tier4_autoware_utils::createPoint(0.5, 1.75, 0); +// search_pose.orientation = tier4_autoware_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); +// const auto closest_lane_obtained4 = +// route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane); + +// ASSERT_TRUE(closest_lane_obtained4); +// ASSERT_EQ(closest_lane.id(), 4424); + +// search_pose.position = tier4_autoware_utils::createPoint(1.0, 1.75, 0); +// search_pose.orientation = tier4_autoware_utils::createQuaternion(0.0, 0.0, 0.0, 1.0); +// const auto closest_lane_obtained5 = +// route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lane); + +// ASSERT_TRUE(closest_lane_obtained5); +// ASSERT_EQ(closest_lane.id(), 4424); +// } +} // namespace route_handler::test diff --git a/planning/route_handler/test/test_route_handler.hpp b/planning/route_handler/test/test_route_handler.hpp new file mode 100644 index 0000000000000..3c6893da3f9d1 --- /dev/null +++ b/planning/route_handler/test/test_route_handler.hpp @@ -0,0 +1,73 @@ +// Copyright 2024 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. + +#ifndef TEST_ROUTE_HANDLER_HPP_ +#define TEST_ROUTE_HANDLER_HPP_ + +#include "ament_index_cpp/get_package_share_directory.hpp" +#include "gtest/gtest.h" +#include "planning_test_utils/mock_data_parser.hpp" +#include "planning_test_utils/planning_test_utils.hpp" + +#include +#include +#include +#include +#include +#include +#include + +#include + +#include + +#include +#include +namespace route_handler::test +{ + +using autoware_auto_mapping_msgs::msg::HADMapBin; + +class TestRouteHandler : public ::testing::Test +{ +public: + TestRouteHandler() + { + const auto planning_test_utils_dir = + ament_index_cpp::get_package_share_directory("planning_test_utils"); + const auto lanelet2_path = planning_test_utils_dir + "/test_map/2km_test.osm"; + constexpr double center_line_resolution = 5.0; + const auto map_bin_msg = test_utils::make_map_bin_msg(lanelet2_path, center_line_resolution); + route_handler_ = std::make_shared(map_bin_msg); + set_lane_change_test_route(); + } + + TestRouteHandler(const TestRouteHandler &) = delete; + TestRouteHandler(TestRouteHandler &&) = delete; + TestRouteHandler & operator=(const TestRouteHandler &) = delete; + TestRouteHandler & operator=(TestRouteHandler &&) = delete; + ~TestRouteHandler() override = default; + + void set_lane_change_test_route() + { + const auto route_handler_dir = ament_index_cpp::get_package_share_directory("route_handler"); + const auto rh_test_route = route_handler_dir + "/test_route/lane_change_test_route.yaml"; + route_handler_->setRoute(test_utils::parse_lanelet_route_file(rh_test_route)); + } + + std::shared_ptr route_handler_; +}; +} // namespace route_handler::test + +#endif // TEST_ROUTE_HANDLER_HPP_ diff --git a/planning/route_handler/test_route/lane_change_test_route.yaml b/planning/route_handler/test_route/lane_change_test_route.yaml new file mode 100644 index 0000000000000..8b4c423c622a0 --- /dev/null +++ b/planning/route_handler/test_route/lane_change_test_route.yaml @@ -0,0 +1,93 @@ +header: + stamp: + sec: 1715936953 + nanosec: 67206425 + frame_id: map +start_pose: + position: + x: -50.0 + y: 1.75 + z: 0.0 + orientation: + x: 0.0 + y: 0.0 + z: 0.0 + w: 1.0 +goal_pose: + position: + x: 70.0 + y: -1.75 + z: 0.0 + orientation: + x: 0.0 + y: 0.0 + z: 0.0 + w: 1.0 +segments: + - preferred_primitive: + id: 4765 + primitive_type: "" + primitives: + - id: 4765 + primitive_type: lane + - id: 9590 + primitive_type: lane + - preferred_primitive: + id: 4770 + primitive_type: "" + primitives: + - id: 4770 + primitive_type: lane + - id: 5072 + primitive_type: lane + - preferred_primitive: + id: 4775 + primitive_type: "" + primitives: + - id: 4775 + primitive_type: lane + - id: 9594 + primitive_type: lane + - preferred_primitive: + id: 9598 + primitive_type: "" + primitives: + - id: 4424 + primitive_type: lane + - id: 9598 + primitive_type: lane + - preferred_primitive: + id: 5084 + primitive_type: "" + primitives: + - id: 4780 + primitive_type: lane + - id: 5084 + primitive_type: lane + - preferred_primitive: + id: 5088 + primitive_type: "" + primitives: + - id: 4785 + primitive_type: lane + - id: 5088 + primitive_type: lane +uuid: + uuid: + - 231 + - 254 + - 143 + - 227 + - 194 + - 8 + - 220 + - 88 + - 30 + - 194 + - 172 + - 147 + - 127 + - 143 + - 176 + - 133 +allow_modification: false diff --git a/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp b/planning/rtc_interface/include/rtc_interface/rtc_interface.hpp index aed7d42cda5e6..7ab796321e041 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,9 +53,10 @@ 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 removeExpiredCooperateStatus(); void clearCooperateStatus(); bool isActivated(const UUID & uuid) const; bool isRegistered(const UUID & uuid) const; @@ -81,6 +84,7 @@ class RTCInterface rclcpp::Service::SharedPtr srv_auto_mode_; rclcpp::CallbackGroup::SharedPtr callback_group_; rclcpp::TimerBase::SharedPtr timer_; + rclcpp::Clock::SharedPtr clock_; rclcpp::Logger logger_; Module module_; diff --git a/planning/rtc_interface/src/rtc_interface.cpp b/planning/rtc_interface/src/rtc_interface.cpp index a7661f4c419a5..77fe29b41d893 100644 --- a/planning/rtc_interface/src/rtc_interface.cpp +++ b/planning/rtc_interface/src/rtc_interface.cpp @@ -62,9 +62,9 @@ Module getModuleType(const std::string & module_name) module.type = Module::AVOIDANCE_BY_LC_LEFT; } else if (module_name == "avoidance_by_lane_change_right") { module.type = Module::AVOIDANCE_BY_LC_RIGHT; - } else if (module_name == "avoidance_left") { + } else if (module_name == "static_obstacle_avoidance_left") { module.type = Module::AVOIDANCE_LEFT; - } else if (module_name == "avoidance_right") { + } else if (module_name == "static_obstacle_avoidance_right") { module.type = Module::AVOIDANCE_RIGHT; } else if (module_name == "goal_planner") { module.type = Module::GOAL_PLANNER; @@ -81,7 +81,8 @@ Module getModuleType(const std::string & module_name) namespace rtc_interface { RTCInterface::RTCInterface(rclcpp::Node * node, const std::string & name, const bool enable_rtc) -: logger_{node->get_logger().get_child("RTCInterface[" + name + "]")}, +: clock_{node->get_clock()}, + logger_{node->get_logger().get_child("RTCInterface[" + name + "]")}, is_auto_mode_enabled_{!enable_rtc}, is_locked_{false} { @@ -152,7 +153,16 @@ std::vector RTCInterface::validateCooperateCommands( registered_status_.statuses.begin(), registered_status_.statuses.end(), [command](auto & s) { return s.uuid == command.uuid; }); if (itr != registered_status_.statuses.end()) { - response.success = true; + if (itr->state.type == State::WAITING_FOR_EXECUTION || itr->state.type == State::RUNNING) { + response.success = true; + } else { + RCLCPP_WARN_STREAM( + getLogger(), "[validateCooperateCommands] uuid : " + << to_string(command.uuid) + << " state is not WAITING_FOR_EXECUTION or RUNNING. state : " + << itr->state.type << std::endl); + response.success = false; + } } else { RCLCPP_WARN_STREAM( getLogger(), "[validateCooperateCommands] uuid : " << to_string(command.uuid) @@ -174,8 +184,10 @@ void RTCInterface::updateCooperateCommandStatus(const std::vectorcommand_status = command.command; - itr->auto_mode = false; + if (itr->state.type == State::WAITING_FOR_EXECUTION || itr->state.type == State::RUNNING) { + itr->command_status = command.command; + itr->auto_mode = false; + } } } } @@ -201,8 +213,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 +230,7 @@ void RTCInterface::updateCooperateStatus( status.module = module_; status.safe = safe; status.command_status.type = Command::DEACTIVATE; + status.state.type = state; status.start_distance = start_distance; status.finish_distance = finish_distance; status.auto_mode = is_auto_mode_enabled_; @@ -228,6 +241,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; } @@ -263,6 +277,16 @@ 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(), + [this](const auto & status) { return (clock_->now() - status.stamp).seconds() > 10.0; }); + + registered_status_.statuses.erase(itr, registered_status_.statuses.end()); +} + void RTCInterface::clearCooperateStatus() { std::lock_guard lock(mutex_); @@ -278,6 +302,9 @@ bool RTCInterface::isActivated(const UUID & uuid) const [uuid](auto & s) { return s.uuid == uuid; }); if (itr != registered_status_.statuses.end()) { + if (itr->state.type == State::FAILED || itr->state.type == State::SUCCEEDED) { + return false; + } if (itr->auto_mode) { return itr->safe; } else { 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; } 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 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 diff --git a/sensing/gnss_poser/launch/gnss_poser.launch.xml b/sensing/gnss_poser/launch/gnss_poser.launch.xml index 90c3553312dc4..c33f9a7589812 100755 --- a/sensing/gnss_poser/launch/gnss_poser.launch.xml +++ b/sensing/gnss_poser/launch/gnss_poser.launch.xml @@ -7,7 +7,7 @@ - + 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/livox/livox_tag_filter/CMakeLists.txt b/sensing/livox/livox_tag_filter/CMakeLists.txt index 90b5eeed713c0..36c500aefa74d 100644 --- a/sensing/livox/livox_tag_filter/CMakeLists.txt +++ b/sensing/livox/livox_tag_filter/CMakeLists.txt @@ -21,4 +21,5 @@ rclcpp_components_register_node(livox_tag_filter ament_auto_package(INSTALL_TO_SHARE launch + config ) diff --git a/sensing/livox/livox_tag_filter/config/livox_tag_filter.param.yaml b/sensing/livox/livox_tag_filter/config/livox_tag_filter.param.yaml new file mode 100644 index 0000000000000..7b7e8cb5bd61a --- /dev/null +++ b/sensing/livox/livox_tag_filter/config/livox_tag_filter.param.yaml @@ -0,0 +1,19 @@ +/**: + ros__parameters: + ignore_tags: [] + # bit 0~1: Point property based on spatial position + # 00: Normal + # 01: High confidence level of the noise + # 10: Moderate confidence level of the noise + # 11: Low confidence level of the noise + # bit 2~3: Point property based on intensity + # 00: Normal + # 01: High confidence level of the noise + # 10: Moderate confidence level of the noise + # 11: Reserved + # bit 4~5: Return number + # 00: return 0 + # 01: return 1 + # 10: return 2 + # 11: return 3 + # bit 6~7: Reserved diff --git a/sensing/livox/livox_tag_filter/launch/livox_tag_filter.launch.xml b/sensing/livox/livox_tag_filter/launch/livox_tag_filter.launch.xml index 1da6c3074e7e7..331db891358f7 100644 --- a/sensing/livox/livox_tag_filter/launch/livox_tag_filter.launch.xml +++ b/sensing/livox/livox_tag_filter/launch/livox_tag_filter.launch.xml @@ -1,30 +1,11 @@ - - - + - + diff --git a/sensing/livox/livox_tag_filter/schema/livox_tag_filter.schema.json b/sensing/livox/livox_tag_filter/schema/livox_tag_filter.schema.json new file mode 100644 index 0000000000000..74d9881192258 --- /dev/null +++ b/sensing/livox/livox_tag_filter/schema/livox_tag_filter.schema.json @@ -0,0 +1,33 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Livox Tag Filter Parameters", + "type": "object", + "definitions": { + "livox_tag_filter": { + "type": "object", + "properties": { + "ignore_tags": { + "type": "array", + "description": "ignored tags (int array) (See the table in the readme file)", + "default": "[]" + } + }, + "required": ["ignore_tags"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/livox_tag_filter" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/sensing/livox/livox_tag_filter/src/livox_tag_filter_node/livox_tag_filter_node.cpp b/sensing/livox/livox_tag_filter/src/livox_tag_filter_node/livox_tag_filter_node.cpp index 2fd55ce8df6a0..f3216fdcd9b6a 100644 --- a/sensing/livox/livox_tag_filter/src/livox_tag_filter_node/livox_tag_filter_node.cpp +++ b/sensing/livox/livox_tag_filter/src/livox_tag_filter_node/livox_tag_filter_node.cpp @@ -40,7 +40,7 @@ LivoxTagFilterNode::LivoxTagFilterNode(const rclcpp::NodeOptions & node_options) : Node("livox_tag_filter", node_options) { // Parameter - ignore_tags_ = this->declare_parameter("ignore_tags", std::vector{}); + ignore_tags_ = this->declare_parameter>("ignore_tags"); // Subscriber using std::placeholders::_1; diff --git a/sensing/pointcloud_preprocessor/docs/ring-outlier-filter.md b/sensing/pointcloud_preprocessor/docs/ring-outlier-filter.md index 61f65bc40f32d..e87023ef00149 100644 --- a/sensing/pointcloud_preprocessor/docs/ring-outlier-filter.md +++ b/sensing/pointcloud_preprocessor/docs/ring-outlier-filter.md @@ -10,6 +10,40 @@ A method of operating scan in chronological order and removing noise based on th ![ring_outlier_filter](./image/outlier_filter-ring.drawio.svg) +Another feature of this node is that it calculates visibility score based on outlier pointcloud and publish score as a topic. + +### visibility score calculation algorithm + +The pointcloud is divided into vertical bins (rings) and horizontal bins (azimuth divisions). +The algorithm starts by splitting the input point cloud into separate rings based on the ring value of each point. Then, for each ring, it iterates through the points and calculates the frequency of points within each horizontal bin. The frequency is determined by incrementing a counter for the corresponding bin based on the point's azimuth value. +The frequency values are stored in a frequency image matrix, where each cell represents a specific ring and azimuth bin. After calculating the frequency image, the algorithm applies a noise threshold to create a binary image. Points with frequency values above the noise threshold are considered valid, while points below the threshold are considered noise. +Finally, the algorithm calculates the visibility score by counting the number of non-zero pixels in the frequency image and dividing it by the total number of pixels (vertical bins multiplied by horizontal bins). + +```plantuml +@startuml +start + +:Convert input point cloud to PCL format; + +:Initialize vertical and horizontal bins; + +:Split point cloud into rings; + +while (For each ring) is (not empty) + :Calculate frequency of points in each azimuth bin; + :Update frequency image matrix; +endwhile + +:Apply noise threshold to create binary image; + +:Count non-zero pixels in frequency image; + +:Calculate visibility score as complement of filled pixel ratio; + +stop +@enduml +``` + ## Inputs / Outputs This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md). @@ -22,14 +56,20 @@ This implementation inherits `pointcloud_preprocessor::Filter` class, please ref ### Core Parameters -| Name | Type | Default Value | Description | -| ---------------------------- | ------- | ------------- | -------------------------------------------------------------------------------------------------------- | -| `distance_ratio` | double | 1.03 | | -| `object_length_threshold` | double | 0.1 | | -| `num_points_threshold` | int | 4 | | -| `max_rings_num` | uint_16 | 128 | | -| `max_points_num_per_ring` | size_t | 4000 | Set this value large enough such that `HFoV / resolution < max_points_num_per_ring` | -| `publish_outlier_pointcloud` | bool | false | Flag to publish outlier pointcloud. Due to performance concerns, please set to false during experiments. | +| Name | Type | Default Value | Description | +| ---------------------------- | ------- | ------------- | ----------------------------------------------------------------------------------------------------------------------------- | +| `distance_ratio` | double | 1.03 | | +| `object_length_threshold` | double | 0.1 | | +| `num_points_threshold` | int | 4 | | +| `max_rings_num` | uint_16 | 128 | | +| `max_points_num_per_ring` | size_t | 4000 | Set this value large enough such that `HFoV / resolution < max_points_num_per_ring` | +| `publish_outlier_pointcloud` | bool | false | Flag to publish outlier pointcloud and visibility score. Due to performance concerns, please set to false during experiments. | +| `min_azimuth_deg` | float | 0.0 | The left limit of azimuth for visibility score calculation | +| `max_azimuth_deg` | float | 360.0 | The right limit of azimuth for visibility score calculation | +| `max_distance` | float | 12.0 | The limit distance for visibility score calculation | +| `vertical_bins` | int | 128 | The number of vertical bin for visibility histogram | +| `horizontal_bins` | int | 36 | The number of horizontal bin for visibility histogram | +| `noise_threshold` | int | 2 | The threshold value for distinguishing noise from valid points in the frequency image | ## Assumptions / Known limits diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp index d92b511d40c69..d80e62d08330d 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp @@ -45,16 +45,22 @@ class FasterVoxelGridDownsampleFilter float x; float y; float z; + float intensity; uint32_t point_count_; - Centroid() : x(0), y(0), z(0) {} - Centroid(float _x, float _y, float _z) : x(_x), y(_y), z(_z) { this->point_count_ = 1; } + Centroid() : x(0), y(0), z(0), intensity(-1.0) {} + Centroid(float _x, float _y, float _z, float _intensity) + : x(_x), y(_y), z(_z), intensity(_intensity) + { + this->point_count_ = 1; + } - void add_point(float _x, float _y, float _z) + void add_point(float _x, float _y, float _z, float _intensity) { this->x += _x; this->y += _y; this->z += _z; + this->intensity += _intensity; this->point_count_++; } @@ -62,20 +68,20 @@ class FasterVoxelGridDownsampleFilter { Eigen::Vector4f centroid( (this->x / this->point_count_), (this->y / this->point_count_), - (this->z / this->point_count_), 1.0f); + (this->z / this->point_count_), (this->intensity / this->point_count_)); return centroid; } }; Eigen::Vector3f inverse_voxel_size_; - std::vector xyz_fields_; int x_offset_; int y_offset_; int z_offset_; + int intensity_index_; int intensity_offset_; bool offset_initialized_; - Eigen::Vector3f get_point_from_global_offset( + Eigen::Vector4f get_point_from_global_offset( const PointCloud2ConstPtr & input, size_t global_offset); bool get_min_max_voxel( diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp index c871f1acbe5b9..55ba79aac4593 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp @@ -19,9 +19,17 @@ #include "pointcloud_preprocessor/filter.hpp" #include "pointcloud_preprocessor/transform_info.hpp" +#include #include +#if __has_include() +#include +#else +#include +#endif + #include +#include #include #include @@ -42,6 +50,8 @@ class RingOutlierFilterComponent : public pointcloud_preprocessor::Filter const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output, const TransformInfo & transform_info); + rclcpp::Publisher::SharedPtr visibility_pub_; + private: /** \brief publisher of excluded pointcloud for debug reason. **/ rclcpp::Publisher::SharedPtr outlier_pointcloud_publisher_; @@ -53,6 +63,15 @@ class RingOutlierFilterComponent : public pointcloud_preprocessor::Filter size_t max_points_num_per_ring_; bool publish_outlier_pointcloud_; + // for visibility score + int noise_threshold_; + int vertical_bins_; + int horizontal_bins_; + + float min_azimuth_deg_; + float max_azimuth_deg_; + float max_distance_; + /** \brief Parameter service callback result : needed to be hold */ OnSetParametersCallbackHandle::SharedPtr set_param_res_; @@ -77,6 +96,7 @@ class RingOutlierFilterComponent : public pointcloud_preprocessor::Filter void setUpPointCloudFormat( const PointCloud2ConstPtr & input, PointCloud2 & formatted_points, size_t points_size, size_t num_fields); + float calculateVisibilityScore(const PointCloud2 & input); public: PCL_MAKE_ALIGNED_OPERATOR_NEW diff --git a/sensing/pointcloud_preprocessor/package.xml b/sensing/pointcloud_preprocessor/package.xml index d12181f498dea..619bf3180591d 100644 --- a/sensing/pointcloud_preprocessor/package.xml +++ b/sensing/pointcloud_preprocessor/package.xml @@ -11,6 +11,9 @@ Dai Nguyen Kenzo Lobos-Tsunekawa Yihsiang Fang + Yoshi Ri + David Wong + Melike Tanrikulu Apache License 2.0 @@ -21,7 +24,6 @@ ament_cmake_auto autoware_cmake - autoware_auto_geometry autoware_point_types cgal cv_bridge diff --git a/sensing/pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp b/sensing/pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp index 5829277335433..9c07a4ec47cba 100644 --- a/sensing/pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp +++ b/sensing/pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp @@ -19,8 +19,6 @@ namespace pointcloud_preprocessor FasterVoxelGridDownsampleFilter::FasterVoxelGridDownsampleFilter() { - pcl::for_each_type::type>( - pcl::detail::FieldAdder(xyz_fields_)); offset_initialized_ = false; } @@ -36,9 +34,9 @@ void FasterVoxelGridDownsampleFilter::set_field_offsets(const PointCloud2ConstPt x_offset_ = input->fields[pcl::getFieldIndex(*input, "x")].offset; y_offset_ = input->fields[pcl::getFieldIndex(*input, "y")].offset; z_offset_ = input->fields[pcl::getFieldIndex(*input, "z")].offset; - int intensity_index = pcl::getFieldIndex(*input, "intensity"); - if (intensity_index != -1) { - intensity_offset_ = input->fields[intensity_index].offset; + intensity_index_ = pcl::getFieldIndex(*input, "intensity"); + if (intensity_index_ != -1) { + intensity_offset_ = input->fields[intensity_index_].offset; } else { intensity_offset_ = z_offset_ + sizeof(float); } @@ -72,7 +70,7 @@ void FasterVoxelGridDownsampleFilter::filter( output.row_step = voxel_centroid_map.size() * input->point_step; output.data.resize(output.row_step); output.width = voxel_centroid_map.size(); - pcl_conversions::fromPCL(xyz_fields_, output.fields); + output.fields = input->fields; output.is_dense = true; // we filter out invalid points output.height = input->height; output.is_bigendian = input->is_bigendian; @@ -83,13 +81,19 @@ void FasterVoxelGridDownsampleFilter::filter( copy_centroids_to_output(voxel_centroid_map, output, transform_info); } -Eigen::Vector3f FasterVoxelGridDownsampleFilter::get_point_from_global_offset( +Eigen::Vector4f FasterVoxelGridDownsampleFilter::get_point_from_global_offset( const PointCloud2ConstPtr & input, size_t global_offset) { - Eigen::Vector3f point( + float intensity = 0.0; + if (intensity_index_ == -1) { + intensity = -1.0; + } else { + intensity = *reinterpret_cast(&input->data[global_offset + intensity_offset_]); + } + Eigen::Vector4f point( *reinterpret_cast(&input->data[global_offset + x_offset_]), *reinterpret_cast(&input->data[global_offset + y_offset_]), - *reinterpret_cast(&input->data[global_offset + z_offset_])); + *reinterpret_cast(&input->data[global_offset + z_offset_]), intensity); return point; } @@ -102,10 +106,10 @@ bool FasterVoxelGridDownsampleFilter::get_min_max_voxel( max_point.setConstant(-FLT_MAX); for (size_t global_offset = 0; global_offset + input->point_step <= input->data.size(); global_offset += input->point_step) { - Eigen::Vector3f point = get_point_from_global_offset(input, global_offset); + Eigen::Vector4f point = get_point_from_global_offset(input, global_offset); if (std::isfinite(point[0]) && std::isfinite(point[1]), std::isfinite(point[2])) { - min_point = min_point.cwiseMin(point); - max_point = max_point.cwiseMax(point); + min_point = min_point.cwiseMin(point.head<3>()); + max_point = max_point.cwiseMax(point.head<3>()); } } @@ -142,7 +146,7 @@ FasterVoxelGridDownsampleFilter::calc_centroids_each_voxel( for (size_t global_offset = 0; global_offset + input->point_step <= input->data.size(); global_offset += input->point_step) { - Eigen::Vector3f point = get_point_from_global_offset(input, global_offset); + Eigen::Vector4f point = get_point_from_global_offset(input, global_offset); if (std::isfinite(point[0]) && std::isfinite(point[1]), std::isfinite(point[2])) { // Calculate the voxel index to which the point belongs int ijk0 = static_cast(std::floor(point[0] * inverse_voxel_size_[0]) - min_voxel[0]); @@ -152,9 +156,9 @@ FasterVoxelGridDownsampleFilter::calc_centroids_each_voxel( // Add the point to the corresponding centroid if (voxel_centroid_map.find(voxel_id) == voxel_centroid_map.end()) { - voxel_centroid_map[voxel_id] = Centroid(point[0], point[1], point[2]); + voxel_centroid_map[voxel_id] = Centroid(point[0], point[1], point[2], point[3]); } else { - voxel_centroid_map[voxel_id].add_point(point[0], point[1], point[2]); + voxel_centroid_map[voxel_id].add_point(point[0], point[1], point[2], point[3]); } } } diff --git a/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp index 762c62dc03b39..ada7d2616ed38 100644 --- a/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp @@ -14,16 +14,16 @@ #include "pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp" -#include "autoware_auto_geometry/common_3d.hpp" +#include "autoware_point_types/types.hpp" #include -#include - #include #include namespace pointcloud_preprocessor { +using autoware_point_types::PointXYZIRADRT; + RingOutlierFilterComponent::RingOutlierFilterComponent(const rclcpp::NodeOptions & options) : Filter("RingOutlierFilter", options) { @@ -35,6 +35,8 @@ RingOutlierFilterComponent::RingOutlierFilterComponent(const rclcpp::NodeOptions debug_publisher_ = std::make_unique(this, "ring_outlier_filter"); outlier_pointcloud_publisher_ = this->create_publisher("debug/ring_outlier_filter", 1); + visibility_pub_ = create_publisher( + "ring_outlier_filter/debug/visibility", rclcpp::SensorDataQoS()); stop_watch_ptr_->tic("cyclic_time"); stop_watch_ptr_->tic("processing_time"); } @@ -50,6 +52,13 @@ RingOutlierFilterComponent::RingOutlierFilterComponent(const rclcpp::NodeOptions static_cast(declare_parameter("max_points_num_per_ring", 4000)); publish_outlier_pointcloud_ = static_cast(declare_parameter("publish_outlier_pointcloud", false)); + + min_azimuth_deg_ = static_cast(declare_parameter("min_azimuth_deg", 0.0)); + max_azimuth_deg_ = static_cast(declare_parameter("max_azimuth_deg", 360.0)); + max_distance_ = static_cast(declare_parameter("max_distance", 12.0)); + vertical_bins_ = static_cast(declare_parameter("vertical_bins", 128)); + horizontal_bins_ = static_cast(declare_parameter("horizontal_bins", 36)); + noise_threshold_ = static_cast(declare_parameter("noise_threshold", 2)); } using std::placeholders::_1; @@ -73,13 +82,7 @@ void RingOutlierFilterComponent::faster_filter( output.data.resize(output.point_step * input->width); size_t output_size = 0; - // Set up the noise points cloud, if noise points are to be published. - PointCloud2 outlier_points; - size_t outlier_points_size = 0; - if (publish_outlier_pointcloud_) { - outlier_points.point_step = sizeof(PointXYZI); - outlier_points.data.resize(outlier_points.point_step * input->width); - } + pcl::PointCloud::Ptr outlier_pcl(new pcl::PointCloud); const auto ring_offset = input->fields.at(static_cast(autoware_point_types::PointIndex::Ring)).offset; @@ -89,6 +92,10 @@ void RingOutlierFilterComponent::faster_filter( input->fields.at(static_cast(autoware_point_types::PointIndex::Distance)).offset; const auto intensity_offset = input->fields.at(static_cast(autoware_point_types::PointIndex::Intensity)).offset; + const auto return_type_offset = + input->fields.at(static_cast(autoware_point_types::PointIndex::ReturnType)).offset; + const auto time_stamp_offset = + input->fields.at(static_cast(autoware_point_types::PointIndex::TimeStamp)).offset; std::vector> ring2indices; ring2indices.reserve(max_rings_num_); @@ -163,24 +170,32 @@ void RingOutlierFilterComponent::faster_filter( } } else if (publish_outlier_pointcloud_) { for (int i = walk_first_idx; i <= walk_last_idx; i++) { - auto outlier_ptr = - reinterpret_cast(&outlier_points.data[outlier_points_size]); + PointXYZIRADRT outlier_point; auto input_ptr = - reinterpret_cast(&input->data[indices[walk_first_idx]]); + reinterpret_cast(&input->data[indices[walk_first_idx]]); if (transform_info.need_transform) { Eigen::Vector4f p(input_ptr->x, input_ptr->y, input_ptr->z, 1); p = transform_info.eigen_transform * p; - outlier_ptr->x = p[0]; - outlier_ptr->y = p[1]; - outlier_ptr->z = p[2]; + outlier_point.x = p[0]; + outlier_point.y = p[1]; + outlier_point.z = p[2]; } else { - *outlier_ptr = *input_ptr; + outlier_point = *input_ptr; } - const float & intensity = *reinterpret_cast( - &input->data[indices[walk_first_idx] + intensity_offset]); - outlier_ptr->intensity = intensity; - outlier_points_size += outlier_points.point_step; + outlier_point.intensity = *reinterpret_cast( + &input->data[indices[walk_first_idx] + intensity_offset]); + outlier_point.ring = *reinterpret_cast( + &input->data[indices[walk_first_idx] + ring_offset]); + outlier_point.azimuth = *reinterpret_cast( + &input->data[indices[walk_first_idx] + azimuth_offset]); + outlier_point.distance = *reinterpret_cast( + &input->data[indices[walk_first_idx] + distance_offset]); + outlier_point.return_type = *reinterpret_cast( + &input->data[indices[walk_first_idx] + return_type_offset]); + outlier_point.time_stamp = *reinterpret_cast( + &input->data[indices[walk_first_idx] + time_stamp_offset]); + outlier_pcl->push_back(outlier_point); } } @@ -213,21 +228,31 @@ void RingOutlierFilterComponent::faster_filter( } } else if (publish_outlier_pointcloud_) { for (int i = walk_first_idx; i < walk_last_idx; i++) { - auto outlier_ptr = reinterpret_cast(&outlier_points.data[outlier_points_size]); - auto input_ptr = reinterpret_cast(&input->data[indices[i]]); + PointXYZIRADRT outlier_point; + + auto input_ptr = reinterpret_cast(&input->data[indices[i]]); if (transform_info.need_transform) { Eigen::Vector4f p(input_ptr->x, input_ptr->y, input_ptr->z, 1); p = transform_info.eigen_transform * p; - outlier_ptr->x = p[0]; - outlier_ptr->y = p[1]; - outlier_ptr->z = p[2]; + outlier_point.x = p[0]; + outlier_point.y = p[1]; + outlier_point.z = p[2]; } else { - *outlier_ptr = *input_ptr; + outlier_point = *input_ptr; } - const float & intensity = + outlier_point.intensity = *reinterpret_cast(&input->data[indices[i] + intensity_offset]); - outlier_ptr->intensity = intensity; - outlier_points_size += outlier_points.point_step; + outlier_point.ring = + *reinterpret_cast(&input->data[indices[i] + ring_offset]); + outlier_point.azimuth = + *reinterpret_cast(&input->data[indices[i] + azimuth_offset]); + outlier_point.distance = + *reinterpret_cast(&input->data[indices[i] + distance_offset]); + outlier_point.return_type = + *reinterpret_cast(&input->data[indices[i] + return_type_offset]); + outlier_point.time_stamp = + *reinterpret_cast(&input->data[indices[i] + time_stamp_offset]); + outlier_pcl->push_back(outlier_point); } } } @@ -235,8 +260,15 @@ void RingOutlierFilterComponent::faster_filter( setUpPointCloudFormat(input, output, output_size, /*num_fields=*/4); if (publish_outlier_pointcloud_) { - setUpPointCloudFormat(input, outlier_points, outlier_points_size, /*num_fields=*/4); - outlier_pointcloud_publisher_->publish(outlier_points); + PointCloud2 outlier; + pcl::toROSMsg(*outlier_pcl, outlier); + outlier.header = input->header; + outlier_pointcloud_publisher_->publish(outlier); + + tier4_debug_msgs::msg::Float32Stamped visibility_msg; + visibility_msg.data = calculateVisibilityScore(outlier); + visibility_msg.stamp = input->header.stamp; + visibility_pub_->publish(visibility_msg); } // add processing time for debug @@ -288,6 +320,24 @@ rcl_interfaces::msg::SetParametersResult RingOutlierFilterComponent::paramCallba RCLCPP_DEBUG( get_logger(), "Setting new publish_outlier_pointcloud to: %d.", publish_outlier_pointcloud_); } + if (get_param(p, "vertical_bins", vertical_bins_)) { + RCLCPP_DEBUG(get_logger(), "Setting new vertical_bins to: %d.", vertical_bins_); + } + if (get_param(p, "horizontal_bins", horizontal_bins_)) { + RCLCPP_DEBUG(get_logger(), "Setting new horizontal_bins to: %d.", horizontal_bins_); + } + if (get_param(p, "noise_threshold", noise_threshold_)) { + RCLCPP_DEBUG(get_logger(), "Setting new noise_threshold to: %d.", noise_threshold_); + } + if (get_param(p, "max_azimuth_deg", max_azimuth_deg_)) { + RCLCPP_DEBUG(get_logger(), "Setting new max_azimuth_deg to: %f.", max_azimuth_deg_); + } + if (get_param(p, "min_azimuth_deg", min_azimuth_deg_)) { + RCLCPP_DEBUG(get_logger(), "Setting new min_azimuth_deg to: %f.", min_azimuth_deg_); + } + if (get_param(p, "max_distance", max_distance_)) { + RCLCPP_DEBUG(get_logger(), "Setting new max_distance to: %f.", max_distance_); + } rcl_interfaces::msg::SetParametersResult result; result.successful = true; @@ -319,6 +369,61 @@ void RingOutlierFilterComponent::setUpPointCloudFormat( "intensity", 1, sensor_msgs::msg::PointField::FLOAT32); } +float RingOutlierFilterComponent::calculateVisibilityScore( + const sensor_msgs::msg::PointCloud2 & input) +{ + pcl::PointCloud::Ptr input_cloud(new pcl::PointCloud); + pcl::fromROSMsg(input, *input_cloud); + + const uint32_t vertical_bins = vertical_bins_; + const uint32_t horizontal_bins = horizontal_bins_; + const float max_azimuth = max_azimuth_deg_ * 100.0; + const float min_azimuth = min_azimuth_deg_ * 100.0; + + const uint32_t horizontal_resolution = + static_cast((max_azimuth - min_azimuth) / horizontal_bins); + + std::vector> ring_point_clouds(vertical_bins); + cv::Mat frequency_image(cv::Size(horizontal_bins, vertical_bins), CV_8UC1, cv::Scalar(0)); + + // Split points into rings + for (const auto & point : input_cloud->points) { + ring_point_clouds.at(point.ring).push_back(point); + } + + // Calculate frequency for each bin in each ring + for (const auto & ring_points : ring_point_clouds) { + if (ring_points.empty()) continue; + + const uint ring_id = ring_points.front().ring; + std::vector frequency_in_ring(horizontal_bins, 0); + + for (const auto & point : ring_points.points) { + if (point.azimuth < min_azimuth || point.azimuth >= max_azimuth) continue; + if (point.distance >= max_distance_) continue; + + const uint bin_index = + static_cast((point.azimuth - min_azimuth) / horizontal_resolution); + + frequency_in_ring[bin_index]++; + frequency_in_ring[bin_index] = + std::min(frequency_in_ring[bin_index], 255); // Ensure value is within uchar range + + frequency_image.at(ring_id, bin_index) = + static_cast(frequency_in_ring[bin_index]); + } + } + + cv::Mat binary_image; + cv::inRange(frequency_image, noise_threshold_, 255, binary_image); + + const int num_pixels = cv::countNonZero(frequency_image); + const float num_filled_pixels = + static_cast(num_pixels) / static_cast(vertical_bins * horizontal_bins); + + return 1.0f - num_filled_pixels; +} + } // namespace pointcloud_preprocessor #include diff --git a/sensing/radar_tracks_noise_filter/launch/radar_tracks_noise_filter.launch.xml b/sensing/radar_tracks_noise_filter/launch/radar_tracks_noise_filter.launch.xml index 028ca5de6a220..f980bcebf1b6b 100644 --- a/sensing/radar_tracks_noise_filter/launch/radar_tracks_noise_filter.launch.xml +++ b/sensing/radar_tracks_noise_filter/launch/radar_tracks_noise_filter.launch.xml @@ -2,7 +2,7 @@ - + diff --git a/sensing/radar_tracks_noise_filter/src/radar_tracks_noise_filter_node/radar_tracks_noise_filter_node.cpp b/sensing/radar_tracks_noise_filter/src/radar_tracks_noise_filter_node/radar_tracks_noise_filter_node.cpp index 5bd143a42eced..82a0a21ff6fdc 100644 --- a/sensing/radar_tracks_noise_filter/src/radar_tracks_noise_filter_node/radar_tracks_noise_filter_node.cpp +++ b/sensing/radar_tracks_noise_filter/src/radar_tracks_noise_filter_node/radar_tracks_noise_filter_node.cpp @@ -56,7 +56,7 @@ RadarTrackCrossingNoiseFilterNode::RadarTrackCrossingNoiseFilterNode( // Subscriber sub_tracks_ = create_subscription( - "~/input/tracks", rclcpp::QoS{1}, + "~/input/tracks", rclcpp::QoS{1}.best_effort(), std::bind(&RadarTrackCrossingNoiseFilterNode::onTracks, this, std::placeholders::_1)); // Publisher 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 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; } diff --git a/system/component_state_monitor/config/topics.yaml b/system/component_state_monitor/config/topics.yaml index f056892849fbc..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.0 - - module: perception mode: [online, logging_simulation] type: launch diff --git a/system/default_ad_api/CMakeLists.txt b/system/default_ad_api/CMakeLists.txt index 982112189412e..799a73508a061 100644 --- a/system/default_ad_api/CMakeLists.txt +++ b/system/default_ad_api/CMakeLists.txt @@ -5,7 +5,9 @@ find_package(autoware_cmake REQUIRED) autoware_package() ament_auto_add_library(${PROJECT_NAME} SHARED + src/diagnostics.cpp src/fail_safe.cpp + src/heartbeat.cpp src/interface.cpp src/localization.cpp src/motion.cpp @@ -16,13 +18,16 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/vehicle.cpp src/vehicle_info.cpp src/vehicle_door.cpp + src/utils/localization_conversion.cpp src/utils/route_conversion.cpp src/compatibility/autoware_state.cpp ) rclcpp_components_register_nodes(${PROJECT_NAME} "default_ad_api::AutowareStateNode" + "default_ad_api::DiagnosticsNode" "default_ad_api::FailSafeNode" + "default_ad_api::HeartbeatNode" "default_ad_api::InterfaceNode" "default_ad_api::LocalizationNode" "default_ad_api::MotionNode" diff --git a/system/default_ad_api/launch/default_ad_api.launch.py b/system/default_ad_api/launch/default_ad_api.launch.py index cf8fbe7d001bf..ca1575a528db2 100644 --- a/system/default_ad_api/launch/default_ad_api.launch.py +++ b/system/default_ad_api/launch/default_ad_api.launch.py @@ -42,7 +42,9 @@ def get_default_config(): def generate_launch_description(): components = [ create_api_node("autoware_state", "AutowareStateNode"), + create_api_node("diagnostics", "DiagnosticsNode"), create_api_node("fail_safe", "FailSafeNode"), + create_api_node("heartbeat", "HeartbeatNode"), create_api_node("interface", "InterfaceNode"), create_api_node("localization", "LocalizationNode"), create_api_node("motion", "MotionNode"), diff --git a/system/default_ad_api/package.xml b/system/default_ad_api/package.xml index 4e691f7ab3192..f9b5a167bdab1 100644 --- a/system/default_ad_api/package.xml +++ b/system/default_ad_api/package.xml @@ -21,6 +21,7 @@ autoware_planning_msgs component_interface_specs component_interface_utils + diagnostic_graph_utils geographic_msgs geography_utils motion_utils diff --git a/system/default_ad_api/src/diagnostics.cpp b/system/default_ad_api/src/diagnostics.cpp new file mode 100644 index 0000000000000..6eaaa5bf614a6 --- /dev/null +++ b/system/default_ad_api/src/diagnostics.cpp @@ -0,0 +1,81 @@ +// 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 "diagnostics.hpp" + +#include +#include + +namespace default_ad_api +{ + +DiagnosticsNode::DiagnosticsNode(const rclcpp::NodeOptions & options) : Node("diagnostics", options) +{ + using std::placeholders::_1; + + pub_struct_ = create_publisher( + "/api/system/diagnostics/struct", rclcpp::QoS(1).transient_local()); + pub_status_ = create_publisher( + "/api/system/diagnostics/status", rclcpp::QoS(1).best_effort()); + + sub_graph_.register_create_callback(std::bind(&DiagnosticsNode::on_create, this, _1)); + sub_graph_.register_update_callback(std::bind(&DiagnosticsNode::on_update, this, _1)); + sub_graph_.subscribe(*this, 10); +} +void DiagnosticsNode::on_create(DiagGraph::ConstSharedPtr graph) +{ + const auto & units = graph->units(); + const auto & links = graph->links(); + + std::unordered_map unit_indices_; + for (size_t i = 0; i < units.size(); ++i) { + unit_indices_[units[i]] = i; + } + + autoware_adapi_v1_msgs::msg::DiagGraphStruct msg; + msg.stamp = graph->created_stamp(); + msg.id = graph->id(); + msg.nodes.reserve(units.size()); + msg.links.reserve(links.size()); + for (const auto & unit : units) { + msg.nodes.emplace_back(); + msg.nodes.back().path = unit->path(); + } + for (const auto & link : links) { + msg.links.emplace_back(); + msg.links.back().parent = unit_indices_.at(link->parent()); + msg.links.back().child = unit_indices_.at(link->child()); + } + pub_struct_->publish(msg); +} + +void DiagnosticsNode::on_update(DiagGraph::ConstSharedPtr graph) +{ + const auto & units = graph->units(); + + autoware_adapi_v1_msgs::msg::DiagGraphStatus msg; + msg.stamp = graph->updated_stamp(); + msg.id = graph->id(); + msg.nodes.reserve(units.size()); + for (const auto & unit : units) { + msg.nodes.emplace_back(); + msg.nodes.back().level = unit->level(); + } + pub_status_->publish(msg); +} + +} // namespace default_ad_api + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(default_ad_api::DiagnosticsNode) diff --git a/system/default_ad_api/src/diagnostics.hpp b/system/default_ad_api/src/diagnostics.hpp new file mode 100644 index 0000000000000..302ffe39159df --- /dev/null +++ b/system/default_ad_api/src/diagnostics.hpp @@ -0,0 +1,46 @@ +// 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 DIAGNOSTICS_HPP_ +#define DIAGNOSTICS_HPP_ + +#include "diagnostic_graph_utils/subscription.hpp" + +#include + +#include +#include + +namespace default_ad_api +{ + +class DiagnosticsNode : public rclcpp::Node +{ +public: + explicit DiagnosticsNode(const rclcpp::NodeOptions & options); + +private: + using DiagGraph = diagnostic_graph_utils::DiagGraph; + using DiagUnit = diagnostic_graph_utils::DiagUnit; + using DiagLink = diagnostic_graph_utils::DiagLink; + void on_create(DiagGraph::ConstSharedPtr graph); + void on_update(DiagGraph::ConstSharedPtr graph); + rclcpp::Publisher::SharedPtr pub_struct_; + rclcpp::Publisher::SharedPtr pub_status_; + diagnostic_graph_utils::DiagGraphSubscription sub_graph_; +}; + +} // namespace default_ad_api + +#endif // DIAGNOSTICS_HPP_ diff --git a/system/default_ad_api/src/heartbeat.cpp b/system/default_ad_api/src/heartbeat.cpp new file mode 100644 index 0000000000000..4550302bb8bae --- /dev/null +++ b/system/default_ad_api/src/heartbeat.cpp @@ -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. + +#include "heartbeat.hpp" + +#include + +namespace default_ad_api +{ + +HeartbeatNode::HeartbeatNode(const rclcpp::NodeOptions & options) : Node("heartbeat", options) +{ + // Move this function so that the timer no longer holds it as a reference. + const auto on_timer = [this]() { + autoware_ad_api::system::Heartbeat::Message heartbeat; + heartbeat.stamp = now(); + heartbeat.seq = ++sequence_; // Wraps at 65535. + pub_->publish(heartbeat); + }; + + const auto adaptor = component_interface_utils::NodeAdaptor(this); + adaptor.init_pub(pub_); + + const auto period = rclcpp::Rate(10.0).period(); + timer_ = rclcpp::create_timer(this, get_clock(), period, std::move(on_timer)); +} + +} // namespace default_ad_api + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(default_ad_api::HeartbeatNode) diff --git a/common/mission_planner_rviz_plugin/src/mrm_goal.cpp b/system/default_ad_api/src/heartbeat.hpp similarity index 54% rename from common/mission_planner_rviz_plugin/src/mrm_goal.cpp rename to system/default_ad_api/src/heartbeat.hpp index ef5529abfb4a7..d922b88489639 100644 --- a/common/mission_planner_rviz_plugin/src/mrm_goal.cpp +++ b/system/default_ad_api/src/heartbeat.hpp @@ -12,23 +12,29 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "mrm_goal.hpp" +#ifndef HEARTBEAT_HPP_ +#define HEARTBEAT_HPP_ -namespace rviz_plugins -{ +#include +#include + +// This file should be included after messages. +#include "utils/types.hpp" -MrmGoalTool::MrmGoalTool() +namespace default_ad_api { - shortcut_key_ = 'm'; -} -void MrmGoalTool::onInitialize() +class HeartbeatNode : public rclcpp::Node { - GoalTool::onInitialize(); - setName("MRM Goal Pose"); -} +public: + explicit HeartbeatNode(const rclcpp::NodeOptions & options); + +private: + rclcpp::TimerBase::SharedPtr timer_; + Pub pub_; + uint16_t sequence_ = 0; +}; -} // namespace rviz_plugins +} // namespace default_ad_api -#include -PLUGINLIB_EXPORT_CLASS(rviz_plugins::MrmGoalTool, rviz_common::Tool) +#endif // HEARTBEAT_HPP_ diff --git a/system/default_ad_api/src/interface.cpp b/system/default_ad_api/src/interface.cpp index 506a4aa8bf5eb..d53d12afcc499 100644 --- a/system/default_ad_api/src/interface.cpp +++ b/system/default_ad_api/src/interface.cpp @@ -21,7 +21,7 @@ InterfaceNode::InterfaceNode(const rclcpp::NodeOptions & options) : Node("interf { const auto on_interface_version = [](auto, auto res) { res->major = 1; - res->minor = 2; + res->minor = 3; res->patch = 0; }; diff --git a/system/default_ad_api/src/localization.cpp b/system/default_ad_api/src/localization.cpp index 468e02b37644f..97544a7868d9c 100644 --- a/system/default_ad_api/src/localization.cpp +++ b/system/default_ad_api/src/localization.cpp @@ -14,6 +14,8 @@ #include "localization.hpp" +#include "utils/localization_conversion.hpp" + namespace default_ad_api { @@ -23,7 +25,15 @@ LocalizationNode::LocalizationNode(const rclcpp::NodeOptions & options) const auto adaptor = component_interface_utils::NodeAdaptor(this); group_cli_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); adaptor.relay_message(pub_state_, sub_state_); - adaptor.relay_service(cli_initialize_, srv_initialize_, group_cli_); + adaptor.init_cli(cli_initialize_); + adaptor.init_srv(srv_initialize_, this, &LocalizationNode::on_initialize, group_cli_); +} + +void LocalizationNode::on_initialize( + const autoware_ad_api::localization::Initialize::Service::Request::SharedPtr req, + const autoware_ad_api::localization::Initialize::Service::Response::SharedPtr res) +{ + res->status = localization_conversion::convert_call(cli_initialize_, req); } } // namespace default_ad_api diff --git a/system/default_ad_api/src/localization.hpp b/system/default_ad_api/src/localization.hpp index 71517c4c6c769..a24e2110fabd1 100644 --- a/system/default_ad_api/src/localization.hpp +++ b/system/default_ad_api/src/localization.hpp @@ -36,6 +36,10 @@ class LocalizationNode : public rclcpp::Node Pub pub_state_; Cli cli_initialize_; Sub sub_state_; + + void on_initialize( + const autoware_ad_api::localization::Initialize::Service::Request::SharedPtr req, + const autoware_ad_api::localization::Initialize::Service::Response::SharedPtr res); }; } // namespace default_ad_api diff --git a/system/default_ad_api/src/operation_mode.cpp b/system/default_ad_api/src/operation_mode.cpp index 829585ed4b8b4..d4b430ecd0579 100644 --- a/system/default_ad_api/src/operation_mode.cpp +++ b/system/default_ad_api/src/operation_mode.cpp @@ -39,18 +39,15 @@ OperationModeNode::OperationModeNode(const rclcpp::NodeOptions & options) adaptor.init_cli(cli_mode_, group_cli_); adaptor.init_cli(cli_control_, group_cli_); - const std::vector module_names = { - "sensing", "perception", "map", "localization", "planning", "control", "vehicle", "system", + const auto name = "/system/operation_mode/availability"; + const auto qos = rclcpp::QoS(1); + const auto callback = [this](const OperationModeAvailability::ConstSharedPtr msg) { + mode_available_[OperationModeState::Message::STOP] = msg->stop; + mode_available_[OperationModeState::Message::AUTONOMOUS] = msg->autonomous; + mode_available_[OperationModeState::Message::LOCAL] = msg->local; + mode_available_[OperationModeState::Message::REMOTE] = msg->remote; }; - - for (size_t i = 0; i < module_names.size(); ++i) { - const auto name = "/system/component_state_monitor/component/autonomous/" + module_names[i]; - const auto qos = rclcpp::QoS(1).transient_local(); - const auto callback = [this, i, module_names](const ModeChangeAvailable::ConstSharedPtr msg) { - module_states_[module_names[i]] = msg->available; - }; - sub_module_states_.push_back(create_subscription(name, qos, callback)); - } + sub_availability_ = create_subscription(name, qos, callback); timer_ = rclcpp::create_timer( this, get_clock(), rclcpp::Rate(5.0).period(), std::bind(&OperationModeNode::on_timer, this)); @@ -60,8 +57,8 @@ OperationModeNode::OperationModeNode(const rclcpp::NodeOptions & options) mode_available_[OperationModeState::Message::UNKNOWN] = false; mode_available_[OperationModeState::Message::STOP] = true; mode_available_[OperationModeState::Message::AUTONOMOUS] = false; - mode_available_[OperationModeState::Message::LOCAL] = true; - mode_available_[OperationModeState::Message::REMOTE] = true; + mode_available_[OperationModeState::Message::LOCAL] = false; + mode_available_[OperationModeState::Message::REMOTE] = false; } template @@ -135,23 +132,6 @@ void OperationModeNode::on_state(const OperationModeState::Message::ConstSharedP void OperationModeNode::on_timer() { - bool autonomous_available = true; - std::string unhealthy_components = ""; - for (const auto & state : module_states_) { - if (!state.second) { - unhealthy_components += unhealthy_components.empty() ? state.first : ", " + state.first; - } - autonomous_available &= state.second; - } - mode_available_[OperationModeState::Message::AUTONOMOUS] = autonomous_available; - - if (!unhealthy_components.empty()) { - RCLCPP_INFO_THROTTLE( - get_logger(), *get_clock(), 3000, - "%s component state is unhealthy. Autonomous is not available.", - unhealthy_components.c_str()); - } - update_state(); } diff --git a/system/default_ad_api/src/operation_mode.hpp b/system/default_ad_api/src/operation_mode.hpp index 1830b7041b566..7cd609b5eb852 100644 --- a/system/default_ad_api/src/operation_mode.hpp +++ b/system/default_ad_api/src/operation_mode.hpp @@ -25,7 +25,7 @@ #include // TODO(Takagi, Isamu): define interface -#include +#include // This file should be included after messages. #include "utils/types.hpp" @@ -47,7 +47,7 @@ class OperationModeNode : public rclcpp::Node using ChangeToRemote = autoware_ad_api::operation_mode::ChangeToRemote; using OperationModeRequest = system_interface::ChangeOperationMode::Service::Request; using AutowareControlRequest = system_interface::ChangeAutowareControl::Service::Request; - using ModeChangeAvailable = tier4_system_msgs::msg::ModeChangeAvailable; + using OperationModeAvailability = tier4_system_msgs::msg::OperationModeAvailability; OperationModeState::Message curr_state_; OperationModeState::Message prev_state_; @@ -65,9 +65,7 @@ class OperationModeNode : public rclcpp::Node Sub sub_state_; Cli cli_mode_; Cli cli_control_; - - std::unordered_map module_states_; - std::vector::SharedPtr> sub_module_states_; + rclcpp::Subscription::SharedPtr sub_availability_; void on_change_to_stop( const ChangeToStop::Service::Request::SharedPtr req, diff --git a/system/default_ad_api/src/planning.cpp b/system/default_ad_api/src/planning.cpp index 887e1167a7c3e..c40bfac40a135 100644 --- a/system/default_ad_api/src/planning.cpp +++ b/system/default_ad_api/src/planning.cpp @@ -85,7 +85,8 @@ PlanningNode::PlanningNode(const rclcpp::NodeOptions & options) : Node("planning "/planning/velocity_factors/surround_obstacle", "/planning/velocity_factors/traffic_light", "/planning/velocity_factors/virtual_traffic_light", - "/planning/velocity_factors/walkway"}; + "/planning/velocity_factors/walkway", + "/planning/velocity_factors/motion_velocity_planner"}; std::vector steering_factor_topics = { "/planning/steering_factor/avoidance", "/planning/steering_factor/intersection", diff --git a/system/default_ad_api/src/utils/localization_conversion.cpp b/system/default_ad_api/src/utils/localization_conversion.cpp new file mode 100644 index 0000000000000..3ddf259a4a590 --- /dev/null +++ b/system/default_ad_api/src/utils/localization_conversion.cpp @@ -0,0 +1,40 @@ +// 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 "localization_conversion.hpp" + +#include + +namespace default_ad_api::localization_conversion +{ + +InternalInitializeRequest convert_request(const ExternalInitializeRequest & external) +{ + auto internal = std::make_shared(); + internal->pose_with_covariance = external->pose; + internal->method = tier4_localization_msgs::srv::InitializeLocalization::Request::AUTO; + return internal; +} + +ExternalResponse convert_response(const InternalResponse & internal) +{ + // TODO(Takagi, Isamu): check error code correspondence + ExternalResponse external; + external.success = internal.success; + external.code = internal.code; + external.message = internal.message; + return external; +} + +} // namespace default_ad_api::localization_conversion diff --git a/system/default_ad_api/src/utils/localization_conversion.hpp b/system/default_ad_api/src/utils/localization_conversion.hpp new file mode 100644 index 0000000000000..85b6e81e6cd91 --- /dev/null +++ b/system/default_ad_api/src/utils/localization_conversion.hpp @@ -0,0 +1,44 @@ +// 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 UTILS__LOCALIZATION_CONVERSION_HPP_ +#define UTILS__LOCALIZATION_CONVERSION_HPP_ + +#include + +#include +#include + +namespace default_ad_api::localization_conversion +{ + +using ExternalInitializeRequest = + autoware_adapi_v1_msgs::srv::InitializeLocalization::Request::SharedPtr; +using InternalInitializeRequest = + tier4_localization_msgs::srv::InitializeLocalization::Request::SharedPtr; +InternalInitializeRequest convert_request(const ExternalInitializeRequest & external); + +using ExternalResponse = autoware_adapi_v1_msgs::msg::ResponseStatus; +using InternalResponse = autoware_common_msgs::msg::ResponseStatus; +ExternalResponse convert_response(const InternalResponse & internal); + +template +ExternalResponse convert_call(ClientT & client, RequestT & req) +{ + return convert_response(client->call(convert_request(req))->status); +} + +} // namespace default_ad_api::localization_conversion + +#endif // UTILS__LOCALIZATION_CONVERSION_HPP_ diff --git a/system/default_ad_api/test/node/interface_version.py b/system/default_ad_api/test/node/interface_version.py index ccfa3e1101185..63a79e8722be3 100644 --- a/system/default_ad_api/test/node/interface_version.py +++ b/system/default_ad_api/test/node/interface_version.py @@ -30,7 +30,7 @@ if response.major != 1: exit(1) -if response.minor != 2: +if response.minor != 3: exit(1) if response.patch != 0: exit(1) 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; 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..b777df8675bef 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 "automatic_pose_initializer::AutomaticPoseInitializer" + 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(); 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/common/graph/config.cpp b/system/diagnostic_graph_aggregator/src/common/graph/config.cpp index 9005084f84503..c9d281a5c886e 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/config.cpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/config.cpp @@ -232,8 +232,8 @@ void apply_edits(FileConfig & config) if (remove_links.count(link) == 0) { filtered_list.push_back(link); } - unit->list = filtered_list; } + unit->list = filtered_list; } // Remove units and links. 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: diff --git a/system/diagnostic_graph_utils/CMakeLists.txt b/system/diagnostic_graph_utils/CMakeLists.txt index 48af5e8fc304f..b68e7bedb57ed 100644 --- a/system/diagnostic_graph_utils/CMakeLists.txt +++ b/system/diagnostic_graph_utils/CMakeLists.txt @@ -9,12 +9,19 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/lib/subscription.cpp ) -ament_auto_add_executable(dump +ament_auto_add_library(${PROJECT_NAME}_tools SHARED src/node/dump.cpp + src/node/converter.cpp ) -ament_auto_add_executable(converter - src/node/converter.cpp +rclcpp_components_register_node(${PROJECT_NAME}_tools + PLUGIN "diagnostic_graph_utils::DumpNode" + EXECUTABLE dump_node +) + +rclcpp_components_register_node(${PROJECT_NAME}_tools + PLUGIN "diagnostic_graph_utils::ConverterNode" + EXECUTABLE converter_node ) ament_auto_package() diff --git a/system/diagnostic_graph_utils/doc/node/converter.md b/system/diagnostic_graph_utils/doc/node/converter.md index c3db547167474..407a99c87f73e 100644 --- a/system/diagnostic_graph_utils/doc/node/converter.md +++ b/system/diagnostic_graph_utils/doc/node/converter.md @@ -5,7 +5,7 @@ This tool converts `/diagnostics_graph` to `/diagnostics_array` so it can be rea ## Usage ```bash -ros2 run diagnostic_graph_utils converter +ros2 run diagnostic_graph_utils converter_node ``` ## Examples @@ -19,7 +19,7 @@ ros2 launch diagnostic_graph_aggregator example-main.launch.xml Terminal 2: ```bash -ros2 run diagnostic_graph_utils converter +ros2 run diagnostic_graph_utils converter_node ``` Terminal 3: diff --git a/system/diagnostic_graph_utils/doc/node/dump.md b/system/diagnostic_graph_utils/doc/node/dump.md index 090e9679676b6..c76bb85ed75cb 100644 --- a/system/diagnostic_graph_utils/doc/node/dump.md +++ b/system/diagnostic_graph_utils/doc/node/dump.md @@ -5,7 +5,7 @@ This tool displays `/diagnostics_graph` in table format. ## Usage ```bash -ros2 run diagnostic_graph_utils dump +ros2 run diagnostic_graph_utils dump_node ``` ## Examples @@ -19,7 +19,7 @@ ros2 launch diagnostic_graph_aggregator example-main.launch.xml Terminal 2: ```bash -ros2 run diagnostic_graph_utils dump +ros2 run diagnostic_graph_utils dump_node ``` Output: diff --git a/system/diagnostic_graph_utils/include/diagnostic_graph_utils/graph.hpp b/system/diagnostic_graph_utils/include/diagnostic_graph_utils/graph.hpp index b2c6fc752e463..c5b386dbe2c86 100644 --- a/system/diagnostic_graph_utils/include/diagnostic_graph_utils/graph.hpp +++ b/system/diagnostic_graph_utils/include/diagnostic_graph_utils/graph.hpp @@ -55,12 +55,20 @@ class DiagLink public: using DiagLinkStruct = tier4_system_msgs::msg::DiagLinkStruct; using DiagLinkStatus = tier4_system_msgs::msg::DiagLinkStatus; - explicit DiagLink(const DiagLinkStruct & msg) : struct_(msg) {} + DiagLink(const DiagLinkStruct & msg, DiagUnit * parent, DiagUnit * child) : struct_(msg) + { + parent_ = parent; + child_ = child; + } void update(const DiagLinkStatus & msg) { status_ = msg; } + DiagUnit * parent() const { return parent_; } + DiagUnit * child() const { return child_; } private: DiagLinkStruct struct_; DiagLinkStatus status_; + DiagUnit * parent_; + DiagUnit * child_; }; class DiagNode : public DiagUnit @@ -114,6 +122,7 @@ class DiagGraph bool update(const DiagGraphStatus & msg); rclcpp::Time created_stamp() const { return created_stamp_; } rclcpp::Time updated_stamp() const { return updated_stamp_; } + std::string id() const { return id_; } std::vector units() const; std::vector nodes() const; std::vector diags() const; diff --git a/system/diagnostic_graph_utils/package.xml b/system/diagnostic_graph_utils/package.xml index 42d44efb6697e..c5a70363bfecb 100644 --- a/system/diagnostic_graph_utils/package.xml +++ b/system/diagnostic_graph_utils/package.xml @@ -12,6 +12,7 @@ diagnostic_msgs rclcpp + rclcpp_components tier4_system_msgs ament_lint_auto diff --git a/system/diagnostic_graph_utils/src/lib/graph.cpp b/system/diagnostic_graph_utils/src/lib/graph.cpp index f1177c1047bdb..bd4c215a346ed 100644 --- a/system/diagnostic_graph_utils/src/lib/graph.cpp +++ b/system/diagnostic_graph_utils/src/lib/graph.cpp @@ -54,7 +54,7 @@ void DiagGraph::create(const DiagGraphStruct & msg) 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(); + const auto link = links_.emplace_back(std::make_unique(data, parent, child)).get(); parent->add_child({link, child}); } } diff --git a/system/diagnostic_graph_utils/src/node/converter.cpp b/system/diagnostic_graph_utils/src/node/converter.cpp index e9e40fa0a0756..159cc6e0c3cab 100644 --- a/system/diagnostic_graph_utils/src/node/converter.cpp +++ b/system/diagnostic_graph_utils/src/node/converter.cpp @@ -19,7 +19,7 @@ namespace diagnostic_graph_utils { -ConverterNode::ConverterNode() : Node("converter") +ConverterNode::ConverterNode(const rclcpp::NodeOptions & options) : Node("converter", options) { using std::placeholders::_1; pub_array_ = create_publisher("/diagnostics_array", rclcpp::QoS(1)); @@ -40,14 +40,5 @@ void ConverterNode::on_update(DiagGraph::ConstSharedPtr graph) } // 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(); -} +#include +RCLCPP_COMPONENTS_REGISTER_NODE(diagnostic_graph_utils::ConverterNode) diff --git a/system/diagnostic_graph_utils/src/node/converter.hpp b/system/diagnostic_graph_utils/src/node/converter.hpp index 09ce62d7293ec..19364a8ff8240 100644 --- a/system/diagnostic_graph_utils/src/node/converter.hpp +++ b/system/diagnostic_graph_utils/src/node/converter.hpp @@ -28,7 +28,7 @@ namespace diagnostic_graph_utils class ConverterNode : public rclcpp::Node { public: - ConverterNode(); + explicit ConverterNode(const rclcpp::NodeOptions & options); private: using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray; diff --git a/system/diagnostic_graph_utils/src/node/dump.cpp b/system/diagnostic_graph_utils/src/node/dump.cpp index 5fa4922dec1a5..8456a92cbaa9b 100644 --- a/system/diagnostic_graph_utils/src/node/dump.cpp +++ b/system/diagnostic_graph_utils/src/node/dump.cpp @@ -24,7 +24,7 @@ namespace diagnostic_graph_utils { -DumpNode::DumpNode() : Node("dump") +DumpNode::DumpNode(const rclcpp::NodeOptions & options) : Node("dump", options) { using std::placeholders::_1; sub_graph_.register_create_callback(std::bind(&DumpNode::on_create, this, _1)); @@ -132,14 +132,5 @@ void DumpNode::on_update(DiagGraph::ConstSharedPtr graph) } // 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(); -} +#include +RCLCPP_COMPONENTS_REGISTER_NODE(diagnostic_graph_utils::DumpNode) diff --git a/system/diagnostic_graph_utils/src/node/dump.hpp b/system/diagnostic_graph_utils/src/node/dump.hpp index e37a1ea971bf5..c990fb77a53db 100644 --- a/system/diagnostic_graph_utils/src/node/dump.hpp +++ b/system/diagnostic_graph_utils/src/node/dump.hpp @@ -28,7 +28,7 @@ namespace diagnostic_graph_utils class DumpNode : public rclcpp::Node { public: - DumpNode(); + explicit DumpNode(const rclcpp::NodeOptions & options); private: void on_create(DiagGraph::ConstSharedPtr graph); diff --git a/system/dummy_diag_publisher/CMakeLists.txt b/system/dummy_diag_publisher/CMakeLists.txt index cecb317bf9c34..794e7d35e1194 100644 --- a/system/dummy_diag_publisher/CMakeLists.txt +++ b/system/dummy_diag_publisher/CMakeLists.txt @@ -4,11 +4,15 @@ project(dummy_diag_publisher) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_executable(${PROJECT_NAME} - src/dummy_diag_publisher_node.cpp +ament_auto_add_library(${PROJECT_NAME} SHARED src/dummy_diag_publisher_core.cpp ) +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "DummyDiagPublisher" + EXECUTABLE ${PROJECT_NAME}_node +) + ament_auto_package(INSTALL_TO_SHARE launch config diff --git a/system/dummy_diag_publisher/include/dummy_diag_publisher/dummy_diag_publisher_core.hpp b/system/dummy_diag_publisher/include/dummy_diag_publisher/dummy_diag_publisher_core.hpp index 8398c15b8e8f6..071e665ece6ec 100644 --- a/system/dummy_diag_publisher/include/dummy_diag_publisher/dummy_diag_publisher_core.hpp +++ b/system/dummy_diag_publisher/include/dummy_diag_publisher/dummy_diag_publisher_core.hpp @@ -35,7 +35,7 @@ struct DiagConfig class DummyDiagPublisher : public rclcpp::Node { public: - DummyDiagPublisher(); + explicit DummyDiagPublisher(const rclcpp::NodeOptions & options); private: enum Status { diff --git a/system/dummy_diag_publisher/launch/dummy_diag_publisher_node.launch.xml b/system/dummy_diag_publisher/launch/dummy_diag_publisher_node.launch.xml index 8e71ce37543c2..9d9193fb5f7a7 100644 --- a/system/dummy_diag_publisher/launch/dummy_diag_publisher_node.launch.xml +++ b/system/dummy_diag_publisher/launch/dummy_diag_publisher_node.launch.xml @@ -4,7 +4,7 @@ - + diff --git a/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp b/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp index cfe1692c91df9..9abf325e62833 100644 --- a/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp +++ b/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp @@ -245,12 +245,14 @@ void DummyDiagPublisher::onTimer() updater_.force_update(); } -DummyDiagPublisher::DummyDiagPublisher() -: Node( - "dummy_diag_publisher", rclcpp::NodeOptions() - .allow_undeclared_parameters(true) - .automatically_declare_parameters_from_overrides(true)), - updater_(this) +rclcpp::NodeOptions override_options(rclcpp::NodeOptions options) +{ + return options.allow_undeclared_parameters(true).automatically_declare_parameters_from_overrides( + true); +} + +DummyDiagPublisher::DummyDiagPublisher(const rclcpp::NodeOptions & options) +: Node("dummy_diag_publisher", override_options(options)), updater_(this) { // Parameter @@ -277,3 +279,6 @@ DummyDiagPublisher::DummyDiagPublisher() timer_ = rclcpp::create_timer( this, get_clock(), period_ns, std::bind(&DummyDiagPublisher::onTimer, this)); } + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(DummyDiagPublisher) diff --git a/system/dummy_diag_publisher/src/dummy_diag_publisher_node.cpp b/system/dummy_diag_publisher/src/dummy_diag_publisher_node.cpp deleted file mode 100644 index a532e8d1c6d01..0000000000000 --- a/system/dummy_diag_publisher/src/dummy_diag_publisher_node.cpp +++ /dev/null @@ -1,26 +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 "dummy_diag_publisher/dummy_diag_publisher_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; -} diff --git a/system/emergency_handler/CMakeLists.txt b/system/emergency_handler/CMakeLists.txt index b7895b07f6e4c..0475cdbe57dd8 100644 --- a/system/emergency_handler/CMakeLists.txt +++ b/system/emergency_handler/CMakeLists.txt @@ -4,11 +4,16 @@ project(emergency_handler) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_executable(emergency_handler - src/emergency_handler/emergency_handler_node.cpp +ament_auto_add_library(${PROJECT_NAME} SHARED src/emergency_handler/emergency_handler_core.cpp ) +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "EmergencyHandler" + EXECUTABLE ${PROJECT_NAME}_node + EXECUTOR MultiThreadedExecutor +) + ament_auto_package(INSTALL_TO_SHARE launch config diff --git a/system/emergency_handler/include/emergency_handler/emergency_handler_core.hpp b/system/emergency_handler/include/emergency_handler/emergency_handler_core.hpp index 5c76d96e573ab..a78b35be26daf 100644 --- a/system/emergency_handler/include/emergency_handler/emergency_handler_core.hpp +++ b/system/emergency_handler/include/emergency_handler/emergency_handler_core.hpp @@ -53,7 +53,7 @@ struct Param class EmergencyHandler : public rclcpp::Node { public: - EmergencyHandler(); + explicit EmergencyHandler(const rclcpp::NodeOptions & options); private: // Subscribers diff --git a/system/emergency_handler/launch/emergency_handler.launch.xml b/system/emergency_handler/launch/emergency_handler.launch.xml index 308eaf90dbb69..203c13bd94e0a 100644 --- a/system/emergency_handler/launch/emergency_handler.launch.xml +++ b/system/emergency_handler/launch/emergency_handler.launch.xml @@ -16,7 +16,7 @@ - + diff --git a/system/emergency_handler/package.xml b/system/emergency_handler/package.xml index 10282297017b1..97344f9b8c594 100644 --- a/system/emergency_handler/package.xml +++ b/system/emergency_handler/package.xml @@ -18,6 +18,7 @@ autoware_auto_vehicle_msgs nav_msgs rclcpp + rclcpp_components std_msgs std_srvs tier4_system_msgs diff --git a/system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp b/system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp index db3ad40249bfb..2770a14691d95 100644 --- a/system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp +++ b/system/emergency_handler/src/emergency_handler/emergency_handler_core.cpp @@ -18,7 +18,8 @@ #include #include -EmergencyHandler::EmergencyHandler() : Node("emergency_handler") +EmergencyHandler::EmergencyHandler(const rclcpp::NodeOptions & options) +: Node("emergency_handler", options) { // Parameter param_.update_rate = declare_parameter("update_rate"); @@ -459,3 +460,6 @@ bool EmergencyHandler::isStopped() return false; } + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(EmergencyHandler) diff --git a/system/emergency_handler/src/emergency_handler/emergency_handler_node.cpp b/system/emergency_handler/src/emergency_handler/emergency_handler_node.cpp deleted file mode 100644 index 5b60117cc3ff4..0000000000000 --- a/system/emergency_handler/src/emergency_handler/emergency_handler_node.cpp +++ /dev/null @@ -1,32 +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 "emergency_handler/emergency_handler_core.hpp" - -#include - -#include - -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(); - - return 0; -} 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) diff --git a/system/mrm_handler/CMakeLists.txt b/system/mrm_handler/CMakeLists.txt index 7c2174f03a6f3..93e03e7f20ead 100644 --- a/system/mrm_handler/CMakeLists.txt +++ b/system/mrm_handler/CMakeLists.txt @@ -4,11 +4,16 @@ project(mrm_handler) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_executable(mrm_handler - src/mrm_handler/mrm_handler_node.cpp +ament_auto_add_library(${PROJECT_NAME} SHARED src/mrm_handler/mrm_handler_core.cpp ) +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "MrmHandler" + EXECUTABLE ${PROJECT_NAME}_node + EXECUTOR MultiThreadedExecutor +) + ament_auto_package(INSTALL_TO_SHARE launch config diff --git a/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp b/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp index 1dd0f6b081337..c7aaca96aae49 100644 --- a/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp +++ b/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp @@ -60,7 +60,7 @@ struct Param class MrmHandler : public rclcpp::Node { public: - MrmHandler(); + explicit MrmHandler(const rclcpp::NodeOptions & options); private: // type diff --git a/system/mrm_handler/launch/mrm_handler.launch.xml b/system/mrm_handler/launch/mrm_handler.launch.xml index 562134f5301e2..7e761157956df 100644 --- a/system/mrm_handler/launch/mrm_handler.launch.xml +++ b/system/mrm_handler/launch/mrm_handler.launch.xml @@ -18,7 +18,7 @@ - + diff --git a/system/mrm_handler/package.xml b/system/mrm_handler/package.xml index e62091f2984e6..c15bc98a6c190 100644 --- a/system/mrm_handler/package.xml +++ b/system/mrm_handler/package.xml @@ -18,6 +18,7 @@ autoware_auto_vehicle_msgs nav_msgs rclcpp + rclcpp_components std_msgs std_srvs tier4_system_msgs diff --git a/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp b/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp index e8e692f755e2d..5e709946c2f46 100644 --- a/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp +++ b/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp @@ -18,7 +18,7 @@ #include #include -MrmHandler::MrmHandler() : Node("mrm_handler") +MrmHandler::MrmHandler(const rclcpp::NodeOptions & options) : Node("mrm_handler", options) { // Parameter param_.update_rate = declare_parameter("update_rate", 10); @@ -597,3 +597,6 @@ bool MrmHandler::isArrivedAtGoal() return operation_mode_state_->mode == OperationModeState::STOP; } + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(MrmHandler) diff --git a/system/system_diagnostic_monitor/config/map.yaml b/system/system_diagnostic_monitor/config/map.yaml index 45c1db294119f..231ac6eb5fa44 100644 --- a/system/system_diagnostic_monitor/config/map.yaml +++ b/system/system_diagnostic_monitor/config/map.yaml @@ -13,4 +13,4 @@ units: - path: /autoware/map/topic_rate_check/pointcloud_map type: diag node: topic_state_monitor_pointcloud_map - name: map_topic_status" + name: map_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 index b00fcb8a26f68..8e2566a747abf 100644 --- a/system/system_diagnostic_monitor/launch/system_diagnostic_monitor.launch.xml +++ b/system/system_diagnostic_monitor/launch/system_diagnostic_monitor.launch.xml @@ -1,6 +1,8 @@ + + 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; -} 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()); diff --git a/tools/reaction_analyzer/CMakeLists.txt b/tools/reaction_analyzer/CMakeLists.txt new file mode 100644 index 0000000000000..d94a5bd7a794e --- /dev/null +++ b/tools/reaction_analyzer/CMakeLists.txt @@ -0,0 +1,40 @@ +cmake_minimum_required(VERSION 3.14) +project(reaction_analyzer) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +find_package(PCL REQUIRED) +find_package(Eigen3 REQUIRED) + +ament_auto_add_library(reaction_analyzer SHARED + include/reaction_analyzer_node.hpp + src/reaction_analyzer_node.cpp + include/subscriber.hpp + src/subscriber.cpp + include/topic_publisher.hpp + src/topic_publisher.cpp + include/utils.hpp + src/utils.cpp +) + +target_include_directories(reaction_analyzer + SYSTEM PUBLIC + ${PCL_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIR} +) + +target_link_libraries(reaction_analyzer + ${PCL_LIBRARIES} +) + +rclcpp_components_register_node(reaction_analyzer + PLUGIN "reaction_analyzer::ReactionAnalyzerNode" + EXECUTABLE reaction_analyzer_exe +) + +ament_auto_package( + INSTALL_TO_SHARE + param + launch +) diff --git a/tools/reaction_analyzer/README.md b/tools/reaction_analyzer/README.md new file mode 100644 index 0000000000000..f5a22aaf20176 --- /dev/null +++ b/tools/reaction_analyzer/README.md @@ -0,0 +1,229 @@ +# Reaction Analyzer + +## Description + +The main purpose of the reaction analyzer package is to measure the reaction times of various nodes within a ROS-based +autonomous driving simulation environment by subscribing to pre-determined topics. This tool is particularly useful for +evaluating the performance of perception, planning, and control pipelines in response to dynamic changes in the +environment, such as sudden obstacles. To be able to measure both control outputs and perception outputs, it was +necessary to divide the node into two running_mode: `planning_control` and `perception_planning`. + +![ReactionAnalyzerDesign.png](media%2FReactionAnalyzerDesign.png) + +### Planning Control Mode + +In this mode, the reaction analyzer creates a dummy publisher for the PredictedObjects and PointCloud2 topics. In the +beginning of the test, it publishes the initial position of the ego vehicle and the goal position to set the test +environment. Then, it spawns a sudden obstacle in front of the ego vehicle. After the obstacle is spawned, it starts to +search reacted messages of the planning and control nodes in the pre-determined topics. When all the topics are reacted, +it calculates the reaction time of the nodes and statistics by comparing `reacted_times` of each of the nodes +with `spawn_cmd_time`, and it creates a csv file to store the results. + +### Perception Planning Mode + +In this mode, the reaction analyzer reads the rosbag files which are recorded from AWSIM, and it creates a topic +publisher for each topic inside the rosbag to replay the rosbag. It reads two rosbag files: `path_bag_without_object` +and `path_bag_with_object`. Firstly, it replays the `path_bag_without_object` to set the initial position of the ego +vehicle and the goal position. After `spawn_time_after_init` seconds , it replays the `path_bag_with_object` to spawn a +sudden obstacle in front of the ego vehicle. After the obstacle is spawned, it starts to search the reacted messages of +the perception and planning nodes in the pre-determined topics. When all the topics are reacted, it calculates the +reaction time of the nodes and statistics by comparing `reacted_times` of each of the nodes with `spawn_cmd_time`, and +it creates a csv file to store the results. + +#### Point Cloud Publisher Type + +To get better analyze for Perception & Sensing pipeline, the reaction analyzer can publish the point cloud messages in 3 +different ways: `async_header_sync_publish`, `sync_header_sync_publish` or `async_publish`. (`T` is the period of the +lidar's output) + +![PointcloudPublisherType.png](media%2FPointcloudPublisherType.png) + +- `async_header_sync_publish`: It publishes the point cloud messages synchronously with asynchronous header times. It + means that each of the lidar's output will be published at the same time, but the headers of the point cloud messages + includes different timestamps because of the phase difference. +- `sync_header_sync_publish`: It publishes the point cloud messages synchronously with synchronous header times. It + means that each of the lidar's output will be published at the same time, and the headers of the point cloud messages + includes the same timestamps. +- `async_publish`: It publishes the point cloud messages asynchronously. It means that each of the lidar's output will + be published at different times. + +## Usage + +The common parameters you need to define for both running modes are `output_file_path`, `test_iteration`, +and `reaction_chain` list. `output_file_path` is the output file path is the path where the results and statistics +will be stored. `test_iteration` defines how many tests will be performed. The `reaction_chain` list is the list of the +pre-defined topics you want to measure their reaction times. + +**IMPORTANT:** Ensure the `reaction_chain` list is correctly defined: + +- For `perception_planning` mode, **do not** define `Control` nodes. +- For `planning_control` mode, **do not** define `Perception` nodes. + +### Prepared Test Environment + +- Download the demonstration test map from the + link [here](https://github.com/tier4/AWSIM/releases/download/v1.1.0/nishishinjuku_autoware_map.zip). After + downloading, + extract the zip file and use its path as `[MAP_PATH]` in the following commands. + +#### Planning Control Mode + +- You need to define only Planning and Control nodes in the `reaction_chain` list. With the default parameters, + you can start to test with the following command: + +```bash +ros2 launch reaction_analyzer reaction_analyzer.launch.xml running_mode:=planning_control vehicle_model:=sample_vehicle sensor_model:=sample_sensor_kit map_path:=[MAP_PATH] +``` + +After the command, the `simple_planning_simulator` and the `reaction_analyzer` will be launched. It will automatically +start to test. After the test is completed, the results will be stored in the `output_file_path` you defined. + +#### Perception Planning Mode + +- Download the rosbag files from the Google Drive + link [here](https://drive.google.com/file/d/1-Qcv7gYfR-usKOjUH8I997w8I4NMhXlX/view?usp=sharing). +- Extract the zip file and set the path of the `.db3` files to parameters `path_bag_without_object` + and `path_bag_with_object`. +- You can start to test with the following command: + +```bash +ros2 launch reaction_analyzer reaction_analyzer.launch.xml running_mode:=perception_planning vehicle_model:=sample_vehicle sensor_model:=awsim_labs_sensor_kit map_path:=[MAP_PATH] +``` + +After the command, the `e2e_simulator` and the `reaction_analyzer` will be launched. It will automatically start +to test. After the test is completed, the results will be stored in the `output_file_path` you defined. + +#### Prepared Test Environment + +**Scene without object:** +![sc1-awsim.png](media%2Fsc1-awsim.png) +![sc1-rviz.png](media%2Fsc1-rviz.png) + +**Scene object:** +![sc2-awsim.png](media%2Fsc2-awsim.png) +![sc2-rviz.png](media%2Fsc2-rviz.png) + +### Custom Test Environment + +**If you want to run the reaction analyzer with your custom test environment, you need to redefine some of the +parameters. +The parameters you need to redefine are `initialization_pose`, `entity_params`, `goal_pose`, and `topic_publisher` ( +for `perception_planning` mode) parameters.** + +- To set `initialization_pose`, `entity_params`, `goal_pose`: +- Run the AWSIM environment. Tutorial for AWSIM can be found + [here](https://autowarefoundation.github.io/AWSIM/main/GettingStarted/QuickStartDemo/). +- Run the e2e_simulator with the following command: + +```bash +ros2 launch autoware_launch e2e_simulator.launch.xml vehicle_model:=sample_vehicle sensor_model:=awsim_labs_sensor_kit map_path:=[MAP_PATH] +``` + +- After EGO is initialized, you can move the ego vehicle to the desired position by using the `SetGoal` button in the + RViz. +- After the EGO stopped in desired position, please localize the dummy obstacle by using the traffic controller. You can + control the traffic by pressing `ESC` button. + +**After localize EGO and dummy vehicle, we should write the positions of these entities in the map frame +in `reaction_analyzer.param.yaml`. To achieve this:** + +- Get initialization pose from `/awsim/ground_truth/vehicle/pose` topic. +- Get entity params from `/perception/object_recognition/objects` topic. +- Get goal pose from `/planning/mission_planning/goal` topic. + +**PS: `initialization_pose` is only valid for `planning_control` mode.** + +- After the parameters were noted, we should record the rosbags for the test. To record the rosbags, you can use the + following command: + +```bash +ros2 bag record --all +``` + +- You should record two rosbags: one without the object and one with the object. You can use the traffic controller to + spawn the object in front of the EGO vehicle or remove it. + +**NOTE: You should record the rosbags in the same environment with the same position of the EGO vehicle. You don't need +to run Autoware while recording.** + +- After you record the rosbags, you can set the `path_bag_without_object` and `path_bag_with_object` parameters with the + paths of the recorded rosbags. + +## Results + +The results will be stored in the `csv` file format and written to the `output_file_path` you defined. It shows each +pipeline of the Autoware by using header timestamp of the messages, and it reports `Node Latency`, `Pipeline Latency`, +and `Total Latency` +for each of the nodes. + +- `Node Latency`: The time difference between previous and current node's reaction timestamps. If it is the first node + in the pipeline, it is same as `Pipeline Latency`. +- `Pipeline Latency`: The time difference between published time of the message and pipeline header time. +- `Total Latency`: The time difference between the message's published timestamp and the spawn obstacle command sent + timestamp. + +## Parameters + +| Name | Type | Description | +| ---------------------------------------------------------------------------- | ------ | --------------------------------------------------------------------------------------------------------------------------------------------- | +| `timer_period` | double | [s] Period for the main processing timer. | +| `test_iteration` | int | Number of iterations for the test. | +| `output_file_path` | string | Directory path where test results and statistics will be stored. | +| `spawn_time_after_init` | double | [s] Time delay after initialization before spawning objects. Only valid `perception_planning` mode. | +| `spawn_distance_threshold` | double | [m] Distance threshold for spawning objects. Only valid `planning_control` mode. | +| `poses.initialization_pose` | struct | Initial pose of the vehicle, containing `x`, `y`, `z`, `roll`, `pitch`, and `yaw` fields. Only valid `planning_control` mode. | +| `poses.entity_params` | struct | Parameters for entities (e.g., obstacles), containing `x`, `y`, `z`, `roll`, `pitch`, `yaw`, `x_dimension`, `y_dimension`, and `z_dimension`. | +| `poses.goal_pose` | struct | Goal pose of the vehicle, containing `x`, `y`, `z`, `roll`, `pitch`, and `yaw` fields. | +| `topic_publisher.path_bag_without_object` | string | Path to the ROS bag file without objects. Only valid `perception_planning` mode. | +| `topic_publisher.path_bag_with_object` | string | Path to the ROS bag file with objects. Only valid `perception_planning` mode. | +| `topic_publisher.spawned_pointcloud_sampling_distance` | double | [m] Sampling distance for point clouds of spawned objects. Only valid `planning_control` mode. | +| `topic_publisher.dummy_perception_publisher_period` | double | [s] Publishing period for the dummy perception data. Only valid `planning_control` mode. | +| `topic_publisher.pointcloud_publisher.pointcloud_publisher_type` | string | Defines how the PointCloud2 messages are going to be published. Modes explained above. | +| `topic_publisher.pointcloud_publisher.pointcloud_publisher_period` | double | [s] Publishing period of the PointCloud2 messages. | +| `topic_publisher.pointcloud_publisher.publish_only_pointcloud_with_object` | bool | Default false. Publish only the point cloud messages with the object. | +| `reaction_params.first_brake_params.debug_control_commands` | bool | Debug publish flag. | +| `reaction_params.first_brake_params.control_cmd_buffer_time_interval` | double | [s] Time interval for buffering control commands. | +| `reaction_params.first_brake_params.min_number_descending_order_control_cmd` | int | Minimum number of control commands in descending order for triggering brake. | +| `reaction_params.first_brake_params.min_jerk_for_brake_cmd` | double | [m/s³] Minimum jerk value for issuing a brake command. | +| `reaction_params.search_zero_vel_params.max_looking_distance` | double | [m] Maximum looking distance for zero velocity on trajectory | +| `reaction_params.search_entity_params.search_radius` | double | [m] Searching radius for spawned entity. Distance between ego pose and entity pose. | +| `reaction_chain` | struct | List of the nodes with their topics and topic's message types. | + +## Limitations + +- Reaction analyzer has some limitation like `PublisherMessageType`, `SubscriberMessageType` and `ReactionType`. It is + currently supporting following list: + +- **Publisher Message Types:** + + - `sensor_msgs/msg/PointCloud2` + - `sensor_msgs/msg/CameraInfo` + - `sensor_msgs/msg/Image` + - `geometry_msgs/msg/PoseWithCovarianceStamped` + - `sensor_msgs/msg/Imu` + - `autoware_auto_vehicle_msgs/msg/ControlModeReport` + - `autoware_auto_vehicle_msgs/msg/GearReport` + - `autoware_auto_vehicle_msgs/msg/HazardLightsReport` + - `autoware_auto_vehicle_msgs/msg/SteeringReport` + - `autoware_auto_vehicle_msgs/msg/TurnIndicatorsReport` + - `autoware_auto_vehicle_msgs/msg/VelocityReport` + +- **Subscriber Message Types:** + + - `sensor_msgs/msg/PointCloud2` + - `autoware_auto_perception_msgs/msg/DetectedObjects` + - `autoware_auto_perception_msgs/msg/TrackedObjects` + - `autoware_auto_msgs/msg/PredictedObject` + - `autoware_auto_planning_msgs/msg/Trajectory` + - `autoware_auto_control_msgs/msg/AckermannControlCommand` + +- **Reaction Types:** + - `FIRST_BRAKE` + - `SEARCH_ZERO_VEL` + - `SEARCH_ENTITY` + +## Future improvements + +- The reaction analyzer can be improved by adding more reaction types. Currently, it is supporting only `FIRST_BRAKE`, + `SEARCH_ZERO_VEL`, and `SEARCH_ENTITY` reaction types. It can be extended by adding more reaction types for each of + the message types. diff --git a/tools/reaction_analyzer/include/reaction_analyzer_node.hpp b/tools/reaction_analyzer/include/reaction_analyzer_node.hpp new file mode 100644 index 0000000000000..6dc3dd896dc92 --- /dev/null +++ b/tools/reaction_analyzer/include/reaction_analyzer_node.hpp @@ -0,0 +1,158 @@ +// 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 REACTION_ANALYZER_NODE_HPP_ +#define REACTION_ANALYZER_NODE_HPP_ + +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +namespace reaction_analyzer +{ +using autoware_adapi_v1_msgs::msg::LocalizationInitializationState; +using autoware_adapi_v1_msgs::msg::OperationModeState; +using autoware_adapi_v1_msgs::msg::RouteState; +using autoware_adapi_v1_msgs::srv::ChangeOperationMode; +using autoware_auto_perception_msgs::msg::PredictedObject; +using autoware_auto_perception_msgs::msg::PredictedObjects; +using autoware_internal_msgs::msg::PublishedTime; +using geometry_msgs::msg::Pose; +using geometry_msgs::msg::PoseStamped; +using nav_msgs::msg::Odometry; +using sensor_msgs::msg::PointCloud2; + +struct NodeParams +{ + std::string running_mode; + double timer_period; + std::string output_file_path; + size_t test_iteration; + double spawn_time_after_init; + double spawn_distance_threshold; + PoseParams initial_pose; + PoseParams goal_pose; + EntityParams entity_params; +}; + +class ReactionAnalyzerNode : public rclcpp::Node +{ +public: + explicit ReactionAnalyzerNode(rclcpp::NodeOptions node_options); + + Odometry::ConstSharedPtr odometry_ptr_; + +private: + std::mutex mutex_; + RunningMode node_running_mode_; + + // Parameters + NodeParams node_params_; + + // Initialization Variables + geometry_msgs::msg::Pose entity_pose_; + geometry_msgs::msg::PoseWithCovarianceStamped init_pose_; + geometry_msgs::msg::PoseStamped goal_pose_; + + // Subscribers + rclcpp::Subscription::SharedPtr sub_kinematics_; + rclcpp::Subscription::SharedPtr sub_route_state_; + rclcpp::Subscription::SharedPtr sub_localization_init_state_; + rclcpp::Subscription::SharedPtr sub_operation_mode_; + rclcpp::Subscription::SharedPtr + sub_ground_truth_pose_; // Only for perception_planning mode + + // Publishers + rclcpp::Publisher::SharedPtr pub_initial_pose_; + rclcpp::Publisher::SharedPtr pub_goal_pose_; + rclcpp::Publisher::SharedPtr pub_marker_; + + // Variables + std::vector pipeline_map_vector_; + std::optional last_test_environment_init_request_time_; + std::optional test_environment_init_time_; + std::optional spawn_cmd_time_; + std::atomic spawn_object_cmd_{false}; + std::atomic ego_initialized_{false}; + bool is_initialization_requested{false}; + bool is_route_set_{false}; + size_t test_iteration_count_{0}; + visualization_msgs::msg::Marker entity_debug_marker_; + + // Functions + void init_analyzer_variables(); + void init_test_env( + const LocalizationInitializationState::ConstSharedPtr & initialization_state_ptr, + const RouteState::ConstSharedPtr & route_state_ptr, + const OperationModeState::ConstSharedPtr & operation_mode_ptr, + const PoseStamped::ConstSharedPtr & ground_truth_pose_ptr, + const Odometry::ConstSharedPtr & odometry_ptr); + bool init_ego( + const LocalizationInitializationState::ConstSharedPtr & initialization_state_ptr, + const Odometry::ConstSharedPtr & odometry_ptr, const rclcpp::Time & current_time); + bool set_route( + const RouteState::ConstSharedPtr & route_state_ptr, const rclcpp::Time & current_time); + bool check_ego_init_correctly( + const PoseStamped::ConstSharedPtr & ground_truth_pose_ptr, + const Odometry::ConstSharedPtr & odometry_ptr); + void call_operation_mode_service_without_response(); + void spawn_obstacle(const geometry_msgs::msg::Point & ego_pose); + void calculate_results( + const std::map & message_buffers, + const rclcpp::Time & spawn_cmd_time); + void on_timer(); + void reset(); + + // Callbacks + void on_vehicle_pose(Odometry::ConstSharedPtr msg_ptr); + void on_localization_initialization_state( + LocalizationInitializationState::ConstSharedPtr msg_ptr); + void on_route_state(RouteState::ConstSharedPtr msg_ptr); + void on_operation_mode_state(OperationModeState::ConstSharedPtr msg_ptr); + void on_ground_truth_pose(PoseStamped::ConstSharedPtr msg_ptr); + + // Timer + rclcpp::TimerBase::SharedPtr timer_; + + // Client + rclcpp::Client::SharedPtr client_change_to_autonomous_; + + // Pointers + std::unique_ptr topic_publisher_ptr_; + std::unique_ptr subscriber_ptr_; + LocalizationInitializationState::ConstSharedPtr initialization_state_ptr_; + RouteState::ConstSharedPtr current_route_state_ptr_; + OperationModeState::ConstSharedPtr operation_mode_ptr_; + PoseStamped::ConstSharedPtr ground_truth_pose_ptr_; +}; +} // namespace reaction_analyzer + +#endif // REACTION_ANALYZER_NODE_HPP_ diff --git a/tools/reaction_analyzer/include/subscriber.hpp b/tools/reaction_analyzer/include/subscriber.hpp new file mode 100644 index 0000000000000..d14d41da545f7 --- /dev/null +++ b/tools/reaction_analyzer/include/subscriber.hpp @@ -0,0 +1,191 @@ +// 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 SUBSCRIBER_HPP_ +#define SUBSCRIBER_HPP_ +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +namespace reaction_analyzer::subscriber +{ +using autoware_auto_control_msgs::msg::AckermannControlCommand; +using autoware_auto_perception_msgs::msg::DetectedObject; +using autoware_auto_perception_msgs::msg::DetectedObjects; +using autoware_auto_perception_msgs::msg::PredictedObject; +using autoware_auto_perception_msgs::msg::PredictedObjects; +using autoware_auto_perception_msgs::msg::TrackedObject; +using autoware_auto_perception_msgs::msg::TrackedObjects; +using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_internal_msgs::msg::PublishedTime; +using geometry_msgs::msg::Pose; +using nav_msgs::msg::Odometry; +using sensor_msgs::msg::PointCloud2; + +// Buffers to be used to store subscribed messages' data, pipeline Header, and PublishedTime +using MessageBuffer = std::optional; +// We need to store the past AckermannControlCommands to analyze the first brake +using ControlCommandBuffer = std::pair, MessageBuffer>; +// Variant to store different types of buffers +using MessageBufferVariant = std::variant; + +template +struct SubscriberVariables +{ + using ExactTimePolicy = message_filters::sync_policies::ExactTime; + + std::unique_ptr> sub1_; + std::unique_ptr> sub2_; + std::unique_ptr> synchronizer_; + // tmp: only for the messages who don't have header e.g. AckermannControlCommand + std::unique_ptr> cache_; +}; + +// Variant to create subscribers for different message types +using SubscriberVariablesVariant = std::variant< + SubscriberVariables, SubscriberVariables, + SubscriberVariables, SubscriberVariables, + SubscriberVariables, SubscriberVariables>; + +// The configuration of the topic to be subscribed which are defined in reaction_chain +struct TopicConfig +{ + std::string node_name; + std::string topic_address; + std::string time_debug_topic_address; + SubscriberMessageType message_type; +}; + +// Place for the reaction functions' parameter configuration +struct FirstBrakeParams +{ + bool debug_control_commands; + double control_cmd_buffer_time_interval; + size_t min_number_descending_order_control_cmd; + double min_jerk_for_brake_cmd; +}; + +struct SearchZeroVelParams +{ + double max_looking_distance; +}; + +struct SearchEntityParams +{ + double search_radius_offset; +}; + +// Place for the store the reaction parameter configuration (currently only for first brake) +struct ReactionParams +{ + FirstBrakeParams first_brake_params; + SearchZeroVelParams search_zero_vel_params; + SearchEntityParams search_entity_params; +}; + +using ChainModules = std::vector; + +class SubscriberBase +{ +public: + explicit SubscriberBase( + rclcpp::Node * node, Odometry::ConstSharedPtr & odometry, std::atomic & spawn_object_cmd, + const EntityParams & entity_params); + + std::optional> get_message_buffers_map(); + void reset(); + +private: + std::mutex mutex_; + + // Init + rclcpp::Node * node_; + Odometry::ConstSharedPtr odometry_; + std::atomic & spawn_object_cmd_; + EntityParams entity_params_; + + // Variables to be initialized in constructor + ChainModules chain_modules_{}; + ReactionParams reaction_params_{}; + geometry_msgs::msg::Pose entity_pose_{}; + double entity_search_radius_{0.0}; + + // Variants + std::map subscriber_variables_map_; + std::map message_buffers_; + + // tf + std::shared_ptr tf_buffer_; + std::shared_ptr tf_listener_; + + // Functions + void init_reaction_chains_and_params(); + bool init_subscribers(); + std::optional get_subscriber_variable( + const TopicConfig & topic_config); + std::optional find_first_brake_idx( + const std::vector & cmd_array); + void set_control_command_to_buffer( + std::vector & buffer, const AckermannControlCommand & cmd) const; + + // Callbacks for modules are subscribed + void on_control_command( + const std::string & node_name, const AckermannControlCommand::ConstSharedPtr & msg_ptr); + void on_trajectory(const std::string & node_name, const Trajectory::ConstSharedPtr & msg_ptr); + void on_trajectory( + const std::string & node_name, const Trajectory::ConstSharedPtr & msg_ptr, + const PublishedTime::ConstSharedPtr & published_time_ptr); + void on_pointcloud(const std::string & node_name, const PointCloud2::ConstSharedPtr & msg_ptr); + void on_pointcloud( + const std::string & node_name, const PointCloud2::ConstSharedPtr & msg_ptr, + const PublishedTime::ConstSharedPtr & published_time_ptr); + void on_predicted_objects( + const std::string & node_name, const PredictedObjects::ConstSharedPtr & msg_ptr); + void on_predicted_objects( + const std::string & node_name, const PredictedObjects::ConstSharedPtr & msg_ptr, + const PublishedTime::ConstSharedPtr & published_time_ptr); + void on_detected_objects( + const std::string & node_name, const DetectedObjects::ConstSharedPtr & msg_ptr); + void on_detected_objects( + const std::string & node_name, const DetectedObjects::ConstSharedPtr & msg_ptr, + const PublishedTime::ConstSharedPtr & published_time_ptr); + void on_tracked_objects( + const std::string & node_name, const TrackedObjects::ConstSharedPtr & msg_ptr); + void on_tracked_objects( + const std::string & node_name, const TrackedObjects::ConstSharedPtr & msg_ptr, + const PublishedTime::ConstSharedPtr & published_time_ptr); +}; + +} // namespace reaction_analyzer::subscriber + +#endif // SUBSCRIBER_HPP_ diff --git a/tools/reaction_analyzer/include/topic_publisher.hpp b/tools/reaction_analyzer/include/topic_publisher.hpp new file mode 100644 index 0000000000000..c6d3a90650884 --- /dev/null +++ b/tools/reaction_analyzer/include/topic_publisher.hpp @@ -0,0 +1,249 @@ +// 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 TOPIC_PUBLISHER_HPP_ +#define TOPIC_PUBLISHER_HPP_ + +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +namespace reaction_analyzer::topic_publisher +{ +using autoware_auto_control_msgs::msg::AckermannControlCommand; +using autoware_auto_perception_msgs::msg::DetectedObject; +using autoware_auto_perception_msgs::msg::DetectedObjects; +using autoware_auto_perception_msgs::msg::PredictedObject; +using autoware_auto_perception_msgs::msg::PredictedObjects; +using autoware_auto_planning_msgs::msg::Trajectory; +using geometry_msgs::msg::Pose; +using nav_msgs::msg::Odometry; +using sensor_msgs::msg::PointCloud2; + +struct TopicPublisherParams +{ + double dummy_perception_publisher_period; // Only for planning_control mode + double spawned_pointcloud_sampling_distance; + std::string path_bag_without_object; // Path to the bag file without object + std::string path_bag_with_object; // Path to the bag file with object + std::string pointcloud_publisher_type; // Type of the pointcloud publisher + double pointcloud_publisher_period; // Period of the pointcloud publisher + bool publish_only_pointcloud_with_object; // Publish only pointcloud with object for only + // perception pipeline debug purpose make it true. +}; + +enum class PointcloudPublisherType { + ASYNC_PUBLISHER = 0, // Asynchronous publisher + SYNC_HEADER_SYNC_PUBLISHER = 1, // Synchronous publisher with header synchronization + ASYNC_HEADER_SYNC_PUBLISHER = 2, // Asynchronous publisher with header synchronization +}; + +/** + * @brief Message type template struct for the variables of the Publisher. + */ +template +struct PublisherVariables +{ + std::chrono::milliseconds period_ms{0}; + typename MessageType::SharedPtr empty_area_message; + typename MessageType::SharedPtr object_spawned_message; + typename rclcpp::Publisher::SharedPtr publisher; + rclcpp::TimerBase::SharedPtr timer; +}; + +/** + * @brief Struct for accessing the variables of the Publisher. + */ +struct PublisherVarAccessor +{ + // Template struct to check if a type has a header member. + template > + struct HasHeader : std::false_type + { + }; + + template + struct HasHeader> : std::true_type + { + }; + + // Template struct to check if a type has a stamp member. + template > + struct HasStamp : std::false_type + { + }; + + template + struct HasStamp> : std::true_type + { + }; + + template + void publish_with_current_time( + const PublisherVariables & publisher_var, const rclcpp::Time & current_time, + const bool is_object_spawned) const + { + std::unique_ptr msg_to_be_published = std::make_unique(); + + if (is_object_spawned) { + *msg_to_be_published = *publisher_var.object_spawned_message; + } else { + *msg_to_be_published = *publisher_var.empty_area_message; + } + if constexpr (HasHeader::value) { + msg_to_be_published->header.stamp = current_time; + } else if constexpr (HasStamp::value) { + msg_to_be_published->stamp = current_time; + } + publisher_var.publisher->publish(std::move(msg_to_be_published)); + } + + template + void set_period(T & publisher_var, std::chrono::milliseconds new_period) + { + publisher_var.period_ms = new_period; + } + + template + std::chrono::milliseconds get_period(const T & publisher_var) const + { + return publisher_var.period_ms; + } + + template + std::shared_ptr get_empty_area_message(const T & publisher_var) const + { + return std::static_pointer_cast(publisher_var.empty_area_message); + } + + template + std::shared_ptr get_object_spawned_message(const T & publisher_var) const + { + return std::static_pointer_cast(publisher_var.object_spawned_message); + } +}; + +using PublisherVariablesVariant = std::variant< + PublisherVariables, PublisherVariables, + PublisherVariables, + PublisherVariables, + PublisherVariables, PublisherVariables, + PublisherVariables, + PublisherVariables, + PublisherVariables, + PublisherVariables, + PublisherVariables, + PublisherVariables, + PublisherVariables>; + +using LidarOutputPair = std::pair< + std::shared_ptr>, + std::shared_ptr>>; + +class TopicPublisher +{ +public: + explicit TopicPublisher( + rclcpp::Node * node, std::atomic & spawn_object_cmd, std::atomic & ego_initialized, + std::optional & spawn_cmd_time, const RunningMode & node_running_mode, + const EntityParams & entity_params); + + void reset(); + +private: + std::mutex mutex_; + + // Initialized variables + rclcpp::Node * node_; + RunningMode node_running_mode_; + std::atomic & spawn_object_cmd_; + std::atomic & ego_initialized_; // used for planning_control mode because if pointcloud is + // published before ego is initialized, it causes crash + EntityParams entity_params_; + std::optional & spawn_cmd_time_; // Set by a publisher function when the + // spawn_object_cmd_ is true + + // tf + std::shared_ptr tf_buffer_; + std::shared_ptr tf_listener_; + + // Parameters + TopicPublisherParams topic_publisher_params_; + + // Variables planning_control mode + rclcpp::Publisher::SharedPtr pub_pointcloud_; + rclcpp::Publisher::SharedPtr pub_predicted_objects_; + PointCloud2::SharedPtr entity_pointcloud_ptr_; + PredictedObjects::SharedPtr predicted_objects_ptr_; + + // Variables perception_planning mode + PointcloudPublisherType pointcloud_publisher_type_; + std::map topic_publisher_map_; + std::map + lidar_pub_variable_pair_map_; // used to publish pointcloud_raw and pointcloud_raw_ex + bool is_object_spawned_message_published_{false}; + std::shared_ptr one_shot_timer_shared_ptr_; + + // Functions + template + void set_message( + const std::string & topic_name, const rosbag2_storage::SerializedBagMessage & bag_message, + const bool is_empty_area_message); + void set_period(const std::map> & time_map); + void set_publishers_and_timers_to_variable(); + void set_timers_for_pointcloud_msgs( + const std::map> & pointcloud_variables_map); + bool check_publishers_initialized_correctly(); + void init_rosbag_publishers(); + void init_rosbag_publisher_buffer(const std::string & bag_path, const bool is_empty_area_message); + void pointcloud_messages_sync_publisher(const PointcloudPublisherType type); + void pointcloud_messages_async_publisher( + const std::pair< + std::shared_ptr>, + std::shared_ptr>> & lidar_output_pair_); + void generic_message_publisher(const std::string & topic_name); + void dummy_perception_publisher(); // Only for planning_control mode + + // Timers + std::map pointcloud_publish_timers_map_; + rclcpp::TimerBase::SharedPtr pointcloud_sync_publish_timer_; + rclcpp::TimerBase::SharedPtr dummy_perception_timer_; +}; +} // namespace reaction_analyzer::topic_publisher + +#endif // TOPIC_PUBLISHER_HPP_ diff --git a/tools/reaction_analyzer/include/utils.hpp b/tools/reaction_analyzer/include/utils.hpp new file mode 100644 index 0000000000000..da1defc03f34c --- /dev/null +++ b/tools/reaction_analyzer/include/utils.hpp @@ -0,0 +1,363 @@ +// 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 UTILS_HPP_ +#define UTILS_HPP_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +// The reaction_analyzer namespace contains utility functions for the Reaction Analyzer tool. +namespace reaction_analyzer +{ +using autoware_auto_control_msgs::msg::AckermannControlCommand; +using autoware_auto_perception_msgs::msg::DetectedObject; +using autoware_auto_perception_msgs::msg::DetectedObjects; +using autoware_auto_perception_msgs::msg::PredictedObject; +using autoware_auto_perception_msgs::msg::PredictedObjects; +using autoware_auto_perception_msgs::msg::TrackedObject; +using autoware_auto_perception_msgs::msg::TrackedObjects; +using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_auto_planning_msgs::msg::TrajectoryPoint; +using autoware_internal_msgs::msg::PublishedTime; +using sensor_msgs::msg::PointCloud2; + +/** + * @brief A pair containing the ReactionPair. + * The first element is name of the node that published the PublishedTime msg. + * The second element is the PublishedTime msg itself + */ +using ReactionPair = std::pair; + +/** + * @brief A map containing the pipeline and the reaction pairs. + * The key is the time at which the pipeline was executed. + * The value is a vector of ReactionPair. + */ +using PipelineMap = std::map>; + +/** + * @brief A vector containing the pipeline and the reaction pairs. + * The first element is the time at which the pipeline was executed. + * The second element is a vector of ReactionPair. + */ +using TimestampedReactionPairsVector = + std::vector>>; + +/** + * @brief Enum for the different types of messages that can be published. + */ +enum class PublisherMessageType { + UNKNOWN = 0, + CAMERA_INFO = 1, + IMAGE = 2, + POINTCLOUD2 = 3, + POSE_WITH_COVARIANCE_STAMPED = 4, + POSE_STAMPED = 5, + ODOMETRY = 6, + IMU = 7, + CONTROL_MODE_REPORT = 8, + GEAR_REPORT = 9, + HAZARD_LIGHTS_REPORT = 10, + STEERING_REPORT = 11, + TURN_INDICATORS_REPORT = 12, + VELOCITY_REPORT = 13, +}; + +/** + * @brief Enum for the different types of messages that can be subscribed to. + */ +enum class SubscriberMessageType { + UNKNOWN = 0, + ACKERMANN_CONTROL_COMMAND = 1, + TRAJECTORY = 2, + POINTCLOUD2 = 3, + DETECTED_OBJECTS = 4, + PREDICTED_OBJECTS = 5, + TRACKED_OBJECTS = 6, +}; + +/** + * @brief Enum for the different types of reactions that can be analyzed. + */ +enum class ReactionType { + UNKNOWN = 0, + FIRST_BRAKE = 1, + SEARCH_ZERO_VEL = 2, + SEARCH_ENTITY = 3, +}; + +/** + * @brief Enum for the different running modes of the Reaction Analyzer. + */ +enum class RunningMode { + PerceptionPlanning = 0, + PlanningControl = 1, +}; + +/** + * @brief Structs containing the parameters of a pose. + */ +struct PoseParams +{ + double x; + double y; + double z; + double roll; + double pitch; + double yaw; +}; + +struct EntityParams +{ + double x; + double y; + double z; + double roll; + double pitch; + double yaw; + double x_l; + double y_l; + double z_l; +}; + +/** + * @brief Struct containing statistics of the latencies. + */ +struct LatencyStats +{ + double min; + double max; + double mean; + double median; + double std_dev; +}; + +/** + * @brief Convert string to SubscriberMessageType. + */ +SubscriberMessageType get_subscriber_message_type(const std::string & message_type); + +/** + * @brief Convert string to PublisherMessageType. + */ +PublisherMessageType get_publisher_message_type(const std::string & message_type); + +/** + * @brief Get the PublisherMessageType for a given topic. + */ +PublisherMessageType get_publisher_message_type_for_topic( + const std::vector & topics, const std::string & topic_name); + +/** + * @brief Convert string to ReactionType. + */ +ReactionType get_reaction_type(const std::string & reaction_type); + +/** + * @brief Calculates the statistics of a vector of latencies. + * @param latency_vec The vector of latencies. + * @return The statistics of the latencies. + */ +LatencyStats calculate_statistics(const std::vector & latency_vec); + +/** + * @brief Generates a UUID message from a string. + * @param input The string to generate the UUID from. + * @return The generated UUID message. + */ +unique_identifier_msgs::msg::UUID generate_uuid_msg(const std::string & input); + +/** + * @brief Generate pose from PoseParams. + * @param pose_params + * @return Pose + */ +geometry_msgs::msg::Pose pose_params_to_pose(const PoseParams & pose_params); + +/** + * @brief Generate entity pose from entity params. + * @param entity_params + * @return Pose + */ +geometry_msgs::msg::Pose create_entity_pose(const EntityParams & entity_params); + +/** + * @brief Generate entity pose from entity params. + * @param entity_params + * @return Pose + */ +double calculate_entity_search_radius(const EntityParams & entity_params); + +/** + * @brief Create a pointcloud from entity params. + * @param entity_params + * @param pointcloud_sampling_distance + * @return PointCloud2::SharedPtr + */ +PointCloud2::SharedPtr create_entity_pointcloud_ptr( + const EntityParams & entity_params, const double pointcloud_sampling_distance); + +/** + * @brief Create a predicted objects message from entity params. + * @param entity_params + * @return PredictedObjects::SharedPtr + */ +PredictedObjects::SharedPtr create_entity_predicted_objects_ptr(const EntityParams & entity_params); + +/** + * @brief Creates a subscription option with a new callback group. + * + * @param node A pointer to the node for which the subscription options are being created. + * @return The created SubscriptionOptions. + */ +rclcpp::SubscriptionOptions create_subscription_options(rclcpp::Node * node); + +/** + * @brief Creates a visualization marker for a polyhedron based on the provided entity parameters. + * + * @param params The parameters of the entity for which the marker is to be created. It includes the + * position, orientation, and dimensions of the entity. + * @return The created visualization marker for the polyhedron. + */ +visualization_msgs::msg::Marker create_polyhedron_marker(const EntityParams & params); + +/** + * @brief Splits a string by a given delimiter. + * + * @param str The string to be split. + * @param delimiter The delimiter to split the string by. + * @return A vector of strings, each of which is a segment of the original string split by the + * delimiter. + */ +std::vector split(const std::string & str, char delimiter); + +/** + * @brief Checks if a folder exists. + * + * @param path The path to the folder. + * @return True if the folder exists, false otherwise. + */ +bool does_folder_exist(const std::string & path); + +/** + * @brief Get the index of the trajectory point that is a certain distance away from the current + * point. + * + * @param traj The trajectory to search. + * @param curr_id The index of the current point in the trajectory. + * @param distance The distance to search for a point. + * @return The index of the point that is at least the specified distance away from the current + * point. + */ +size_t get_index_after_distance( + const Trajectory & traj, const size_t curr_id, const double distance); + +/** + * @brief Search for a pointcloud near the pose. + * @param pcl_pointcloud, pose, search_radius + * @return bool + */ +bool search_pointcloud_near_pose( + const pcl::PointCloud & pcl_pointcloud, const geometry_msgs::msg::Pose & pose, + const double search_radius); +/** + * + * @brief Search for a predicted object near the pose. + * @param predicted_objects, pose, search_radius + * @return bool + */ +bool search_predicted_objects_near_pose( + const PredictedObjects & predicted_objects, const geometry_msgs::msg::Pose & pose, + const double search_radius); +/** + * @brief Search for a detected object near the pose. + * @param detected_objects, pose, search_radius + * @return bool + */ +bool search_detected_objects_near_pose( + const DetectedObjects & detected_objects, const geometry_msgs::msg::Pose & pose, + const double search_radius); +/** + * @brief Search for a tracked object near the pose. + * @param tracked_objects, pose, search_radius + * @return bool + */ +bool search_tracked_objects_near_pose( + const TrackedObjects & tracked_objects, const geometry_msgs::msg::Pose & pose, + const double search_radius); + +/** + * Calculates the time difference in milliseconds between two rclcpp::Time instances. + * + * @param start The start time. + * @param end The end time. + * @return The time difference in milliseconds as a double. + */ +double calculate_time_diff_ms(const rclcpp::Time & start, const rclcpp::Time & end); + +/** + * @brief Converts a PipelineMap to a PipelineMapVector. + * + * @param pipelineMap The PipelineMap to be converted. + * @return The PipelineMapVector that is equivalent to the PipelineMap. + */ +TimestampedReactionPairsVector convert_pipeline_map_to_sorted_vector( + const PipelineMap & pipelineMap); + +/** + * @brief Writes the results to a file. + * + * @param node A pointer to the node for which the results are being written. + * @param output_file_path The path to the file where the results will be written. + * @param node_running_mode The running mode of the node. + * @param pipeline_map_vector The vector of PipelineMap containing the results to be written. + */ +void write_results( + rclcpp::Node * node, const std::string & output_file_path, const RunningMode & node_running_mode, + const std::vector & pipeline_map_vector); +} // namespace reaction_analyzer + +#endif // UTILS_HPP_ diff --git a/tools/reaction_analyzer/launch/reaction_analyzer.launch.xml b/tools/reaction_analyzer/launch/reaction_analyzer.launch.xml new file mode 100644 index 0000000000000..b0b1d4fb9bf2e --- /dev/null +++ b/tools/reaction_analyzer/launch/reaction_analyzer.launch.xml @@ -0,0 +1,67 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/tools/reaction_analyzer/media/PointcloudPublisherType.png b/tools/reaction_analyzer/media/PointcloudPublisherType.png new file mode 100644 index 0000000000000..597b73318bcac Binary files /dev/null and b/tools/reaction_analyzer/media/PointcloudPublisherType.png differ diff --git a/tools/reaction_analyzer/media/ReactionAnalyzerDesign.png b/tools/reaction_analyzer/media/ReactionAnalyzerDesign.png new file mode 100644 index 0000000000000..cb0f2dd8577fc Binary files /dev/null and b/tools/reaction_analyzer/media/ReactionAnalyzerDesign.png differ diff --git a/tools/reaction_analyzer/media/sc1-awsim.png b/tools/reaction_analyzer/media/sc1-awsim.png new file mode 100644 index 0000000000000..6bdc104a93b87 Binary files /dev/null and b/tools/reaction_analyzer/media/sc1-awsim.png differ diff --git a/tools/reaction_analyzer/media/sc1-rviz.png b/tools/reaction_analyzer/media/sc1-rviz.png new file mode 100644 index 0000000000000..ae7c6e882bf98 Binary files /dev/null and b/tools/reaction_analyzer/media/sc1-rviz.png differ diff --git a/tools/reaction_analyzer/media/sc2-awsim.png b/tools/reaction_analyzer/media/sc2-awsim.png new file mode 100644 index 0000000000000..8224b516897be Binary files /dev/null and b/tools/reaction_analyzer/media/sc2-awsim.png differ diff --git a/tools/reaction_analyzer/media/sc2-rviz.png b/tools/reaction_analyzer/media/sc2-rviz.png new file mode 100644 index 0000000000000..8f4f5feae8ba3 Binary files /dev/null and b/tools/reaction_analyzer/media/sc2-rviz.png differ diff --git a/tools/reaction_analyzer/package.xml b/tools/reaction_analyzer/package.xml new file mode 100644 index 0000000000000..05081eac01751 --- /dev/null +++ b/tools/reaction_analyzer/package.xml @@ -0,0 +1,49 @@ + + + + reaction_analyzer + 1.0.0 + Analyzer that measures reaction times of the nodes + + Berkay Karaman + + Apache License 2.0 + + Berkay Karaman + + ament_cmake_auto + autoware_cmake + + autoware_adapi_v1_msgs + autoware_auto_control_msgs + autoware_auto_perception_msgs + autoware_auto_planning_msgs + autoware_auto_system_msgs + autoware_auto_vehicle_msgs + autoware_internal_msgs + eigen + libpcl-all-dev + message_filters + motion_utils + pcl_conversions + pcl_ros + rclcpp + rclcpp_components + rosbag2_cpp + sensor_msgs + tf2 + tf2_eigen + tf2_geometry_msgs + tf2_ros + tier4_autoware_utils + + ament_cmake_ros + ament_index_python + ament_lint_auto + autoware_lint_common + autoware_testing + + + ament_cmake + + diff --git a/tools/reaction_analyzer/param/reaction_analyzer.param.yaml b/tools/reaction_analyzer/param/reaction_analyzer.param.yaml new file mode 100644 index 0000000000000..62c1191bd345a --- /dev/null +++ b/tools/reaction_analyzer/param/reaction_analyzer.param.yaml @@ -0,0 +1,117 @@ +/**: + ros__parameters: + timer_period: 0.033 # s + test_iteration: 10 + output_file_path: + spawn_time_after_init: 10.0 # s for perception_planning mode + spawn_distance_threshold: 15.0 # m # for planning_control mode + poses: + initialization_pose: + x: 81546.984375 + y: 50011.96875 + z: 0.0 + roll: 0.0 + pitch: 0.0 + yaw: 11.1130405 + goal_pose: + x: 81643.0703125 + y: 50029.8828125 + z: 0.0 + roll: 0.0 + pitch: 0.0 + yaw: 13.12 + entity_params: + x: 81633.86068376624 + y: 50028.383586673124 + z: 42.44818343779461 + roll: 0.0 + pitch: 0.0 + yaw: 11.8235848 + x_dimension: 3.95 + y_dimension: 1.77 + z_dimension: 1.43 + topic_publisher: + path_bag_without_object: /rosbag2_awsim_labs/rosbag2_awsim_labs.db3 + path_bag_with_object: /rosbag2_awsim_labs_obstacle/rosbag2_awsim_labs_obstacle.db3 + pointcloud_publisher: + pointcloud_publisher_type: "sync_header_sync_publish" # "async_header_sync_publish", "sync_header_sync_publish" or "async_publish" + pointcloud_publisher_period: 0.1 # s + publish_only_pointcloud_with_object: false # use it only for debug purposes. If true, only pointclouds with object will be published + spawned_pointcloud_sampling_distance: 0.1 # m for planning_control mode + dummy_perception_publisher_period: 0.1 # s for planning_control mode + subscriber: + reaction_params: + first_brake_params: + debug_control_commands: false + control_cmd_buffer_time_interval: 1.0 # s + min_number_descending_order_control_cmd: 3 + min_jerk_for_brake_cmd: 0.3 # m/s^3 + search_zero_vel_params: + max_looking_distance: 15.0 # m + search_entity_params: + search_radius_offset: 0.0 # m + reaction_chain: + obstacle_cruise_planner: + topic_name: /planning/scenario_planning/lane_driving/trajectory + time_debug_topic_name: /planning/scenario_planning/lane_driving/trajectory/debug/published_time + message_type: autoware_auto_planning_msgs/msg/Trajectory + scenario_selector: + topic_name: /planning/scenario_planning/scenario_selector/trajectory + time_debug_topic_name: /planning/scenario_planning/scenario_selector/trajectory/debug/published_time + message_type: autoware_auto_planning_msgs/msg/Trajectory + motion_velocity_smoother: + topic_name: /planning/scenario_planning/motion_velocity_smoother/trajectory + time_debug_topic_name: /planning/scenario_planning/motion_velocity_smoother/trajectory/debug/published_time + message_type: autoware_auto_planning_msgs/msg/Trajectory + planning_validator: + topic_name: /planning/scenario_planning/trajectory + time_debug_topic_name: /planning/scenario_planning/trajectory/debug/published_time + message_type: autoware_auto_planning_msgs/msg/Trajectory + trajectory_follower: + topic_name: /control/trajectory_follower/control_cmd + time_debug_topic_name: /control/trajectory_follower/control_cmd/debug/published_time + message_type: autoware_auto_control_msgs/msg/AckermannControlCommand + vehicle_cmd_gate: + topic_name: /control/command/control_cmd + time_debug_topic_name: /control/command/control_cmd/debug/published_time + message_type: autoware_auto_control_msgs/msg/AckermannControlCommand + common_ground_filter: + topic_name: /perception/obstacle_segmentation/single_frame/pointcloud + time_debug_topic_name: /perception/obstacle_segmentation/single_frame/pointcloud/debug/published_time + message_type: sensor_msgs/msg/PointCloud2 + occupancy_grid_map_outlier: + topic_name: /perception/obstacle_segmentation/pointcloud + time_debug_topic_name: /perception/obstacle_segmentation/pointcloud/debug/published_time + message_type: sensor_msgs/msg/PointCloud2 + multi_object_tracker: + topic_name: /perception/object_recognition/tracking/near_objects + time_debug_topic_name: /perception/object_recognition/tracking/near_objects/debug/published_time + message_type: autoware_auto_perception_msgs/msg/TrackedObjects + lidar_centerpoint: + topic_name: /perception/object_recognition/detection/centerpoint/objects + time_debug_topic_name: /perception/object_recognition/detection/centerpoint/objects/debug/published_time + message_type: autoware_auto_perception_msgs/msg/DetectedObjects + obstacle_pointcloud_based_validator: + topic_name: /perception/object_recognition/detection/centerpoint/validation/objects + time_debug_topic_name: /perception/object_recognition/detection/centerpoint/validation/objects/debug/published_time + message_type: autoware_auto_perception_msgs/msg/DetectedObjects + decorative_tracker_merger: + topic_name: /perception/object_recognition/tracking/objects + time_debug_topic_name: /perception/object_recognition/tracking/objects/debug/published_time + message_type: autoware_auto_perception_msgs/msg/TrackedObjects + detected_object_feature_remover: + topic_name: /perception/object_recognition/detection/clustering/objects + time_debug_topic_name: /perception/object_recognition/detection/clustering/objects/debug/published_time + message_type: autoware_auto_perception_msgs/msg/DetectedObjects + detection_by_tracker: + topic_name: /perception/object_recognition/detection/detection_by_tracker/objects + time_debug_topic_name: /perception/object_recognition/detection/detection_by_tracker/objects/debug/published_time + message_type: autoware_auto_perception_msgs/msg/DetectedObjects + object_lanelet_filter: + topic_name: /perception/object_recognition/detection/objects + time_debug_topic_name: /perception/object_recognition/detection/objects/debug/published_time + message_type: autoware_auto_perception_msgs/msg/DetectedObjects + map_based_prediction: + topic_name: /perception/object_recognition/objects + time_debug_topic_name: /perception/object_recognition/objects/debug/published_time + message_type: autoware_auto_perception_msgs/msg/PredictedObjects diff --git a/tools/reaction_analyzer/src/reaction_analyzer_node.cpp b/tools/reaction_analyzer/src/reaction_analyzer_node.cpp new file mode 100644 index 0000000000000..53313f28eb4d9 --- /dev/null +++ b/tools/reaction_analyzer/src/reaction_analyzer_node.cpp @@ -0,0 +1,442 @@ +// 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 "reaction_analyzer_node.hpp" + +#include +#include + +namespace reaction_analyzer +{ + +void ReactionAnalyzerNode::on_operation_mode_state(OperationModeState::ConstSharedPtr msg_ptr) +{ + std::lock_guard lock(mutex_); + operation_mode_ptr_ = std::move(msg_ptr); +} + +void ReactionAnalyzerNode::on_route_state(RouteState::ConstSharedPtr msg_ptr) +{ + std::lock_guard lock(mutex_); + current_route_state_ptr_ = std::move(msg_ptr); +} + +void ReactionAnalyzerNode::on_vehicle_pose(Odometry::ConstSharedPtr msg_ptr) +{ + std::lock_guard lock(mutex_); + odometry_ptr_ = msg_ptr; +} + +void ReactionAnalyzerNode::on_localization_initialization_state( + LocalizationInitializationState::ConstSharedPtr msg_ptr) +{ + std::lock_guard lock(mutex_); + initialization_state_ptr_ = std::move(msg_ptr); +} + +void ReactionAnalyzerNode::on_ground_truth_pose(PoseStamped::ConstSharedPtr msg_ptr) +{ + std::lock_guard lock(mutex_); + ground_truth_pose_ptr_ = std::move(msg_ptr); +} + +ReactionAnalyzerNode::ReactionAnalyzerNode(rclcpp::NodeOptions node_options) +: Node("reaction_analyzer_node", node_options.automatically_declare_parameters_from_overrides(true)) +{ + using std::placeholders::_1; + + node_params_.running_mode = get_parameter("running_mode").as_string(); + + // set running mode + if (node_params_.running_mode == "planning_control") { + node_running_mode_ = RunningMode::PlanningControl; + } else if (node_params_.running_mode == "perception_planning") { + node_running_mode_ = RunningMode::PerceptionPlanning; + } else { + RCLCPP_ERROR(get_logger(), "Invalid running mode. Node couldn't be initialized. Failed."); + return; + } + + node_params_.output_file_path = get_parameter("output_file_path").as_string(); + // Check if the output file path is valid + if (!does_folder_exist(node_params_.output_file_path)) { + RCLCPP_ERROR(get_logger(), "Output file path is not valid. Node couldn't be initialized."); + return; + } + + node_params_.timer_period = get_parameter("timer_period").as_double(); + node_params_.test_iteration = get_parameter("test_iteration").as_int(); + node_params_.spawn_time_after_init = get_parameter("spawn_time_after_init").as_double(); + node_params_.spawn_distance_threshold = get_parameter("spawn_distance_threshold").as_double(); + + // Position parameters + node_params_.initial_pose.x = get_parameter("poses.initialization_pose.x").as_double(); + node_params_.initial_pose.y = get_parameter("poses.initialization_pose.y").as_double(); + node_params_.initial_pose.z = get_parameter("poses.initialization_pose.z").as_double(); + node_params_.initial_pose.roll = get_parameter("poses.initialization_pose.roll").as_double(); + node_params_.initial_pose.pitch = get_parameter("poses.initialization_pose.pitch").as_double(); + node_params_.initial_pose.yaw = get_parameter("poses.initialization_pose.yaw").as_double(); + + node_params_.goal_pose.x = get_parameter("poses.goal_pose.x").as_double(); + node_params_.goal_pose.y = get_parameter("poses.goal_pose.y").as_double(); + node_params_.goal_pose.z = get_parameter("poses.goal_pose.z").as_double(); + node_params_.goal_pose.roll = get_parameter("poses.goal_pose.roll").as_double(); + node_params_.goal_pose.pitch = get_parameter("poses.goal_pose.pitch").as_double(); + node_params_.goal_pose.yaw = get_parameter("poses.goal_pose.yaw").as_double(); + + node_params_.entity_params.x = get_parameter("poses.entity_params.x").as_double(); + node_params_.entity_params.y = get_parameter("poses.entity_params.y").as_double(); + node_params_.entity_params.z = get_parameter("poses.entity_params.z").as_double(); + node_params_.entity_params.roll = get_parameter("poses.entity_params.roll").as_double(); + node_params_.entity_params.pitch = get_parameter("poses.entity_params.pitch").as_double(); + node_params_.entity_params.yaw = get_parameter("poses.entity_params.yaw").as_double(); + node_params_.entity_params.x_l = get_parameter("poses.entity_params.x_dimension").as_double(); + node_params_.entity_params.y_l = get_parameter("poses.entity_params.y_dimension").as_double(); + node_params_.entity_params.z_l = get_parameter("poses.entity_params.z_dimension").as_double(); + + sub_kinematics_ = create_subscription( + "input/kinematics", 1, std::bind(&ReactionAnalyzerNode::on_vehicle_pose, this, _1), + create_subscription_options(this)); + sub_localization_init_state_ = create_subscription( + "input/localization_initialization_state", rclcpp::QoS(1).transient_local(), + std::bind(&ReactionAnalyzerNode::on_localization_initialization_state, this, _1), + create_subscription_options(this)); + sub_route_state_ = create_subscription( + "input/routing_state", rclcpp::QoS{1}.transient_local(), + std::bind(&ReactionAnalyzerNode::on_route_state, this, _1), create_subscription_options(this)); + sub_operation_mode_ = create_subscription( + "input/operation_mode_state", rclcpp::QoS{1}.transient_local(), + std::bind(&ReactionAnalyzerNode::on_operation_mode_state, this, _1), + create_subscription_options(this)); + + pub_goal_pose_ = create_publisher("output/goal", rclcpp::QoS(1)); + pub_marker_ = create_publisher("~/debug", 10); + + init_analyzer_variables(); + + if (node_running_mode_ == RunningMode::PlanningControl) { + pub_initial_pose_ = create_publisher( + "output/initialpose", rclcpp::QoS(1)); + + client_change_to_autonomous_ = + create_client("service/change_to_autonomous"); + + } else if (node_running_mode_ == RunningMode::PerceptionPlanning) { + sub_ground_truth_pose_ = create_subscription( + "input/ground_truth_pose", rclcpp::QoS{1}, + std::bind(&ReactionAnalyzerNode::on_ground_truth_pose, this, _1), + create_subscription_options(this)); + } + + topic_publisher_ptr_ = std::make_unique( + this, spawn_object_cmd_, ego_initialized_, spawn_cmd_time_, node_running_mode_, + node_params_.entity_params); + + // initialize the odometry before init the subscriber + odometry_ptr_ = std::make_shared(); + // Load the subscriber to listen the topics for reactions + subscriber_ptr_ = std::make_unique( + this, odometry_ptr_, spawn_object_cmd_, node_params_.entity_params); + + const auto period_ns = std::chrono::duration_cast( + std::chrono::duration(node_params_.timer_period)); + timer_ = rclcpp::create_timer( + this, get_clock(), period_ns, std::bind(&ReactionAnalyzerNode::on_timer, this)); +} + +void ReactionAnalyzerNode::on_timer() +{ + mutex_.lock(); + const auto current_odometry_ptr = odometry_ptr_; + const auto initialization_state_ptr = initialization_state_ptr_; + const auto route_state_ptr = current_route_state_ptr_; + const auto operation_mode_ptr = operation_mode_ptr_; + const auto ground_truth_pose_ptr = ground_truth_pose_ptr_; + const auto spawn_cmd_time = spawn_cmd_time_; + mutex_.unlock(); + + // Init the test environment + if (!test_environment_init_time_) { + init_test_env( + initialization_state_ptr, route_state_ptr, operation_mode_ptr, ground_truth_pose_ptr, + current_odometry_ptr); + return; + } + + pub_marker_->publish(entity_debug_marker_); + + // Spawn the obstacle if the conditions are met + spawn_obstacle(current_odometry_ptr->pose.pose.position); + + // If the spawn_cmd_time is not set by pointcloud publishers, don't do anything + if (!spawn_cmd_time) return; + + // Get the reacted messages, if all modules reacted + const auto message_buffers = subscriber_ptr_->get_message_buffers_map(); + + if (message_buffers) { + // if reacted, calculate the results + calculate_results(message_buffers.value(), spawn_cmd_time.value()); + // reset the variables if the iteration is not finished, otherwise write the results + reset(); + } +} + +void ReactionAnalyzerNode::spawn_obstacle(const geometry_msgs::msg::Point & ego_pose) +{ + if (node_running_mode_ == RunningMode::PerceptionPlanning) { + rclcpp::Duration time_diff = this->now() - test_environment_init_time_.value(); + if (time_diff > rclcpp::Duration::from_seconds(node_params_.spawn_time_after_init)) { + if (!spawn_object_cmd_) { + spawn_object_cmd_ = true; + RCLCPP_INFO(this->get_logger(), "Spawn command is sent."); + } + } + } else { + if ( + tier4_autoware_utils::calcDistance3d(ego_pose, entity_pose_.position) < + node_params_.spawn_distance_threshold) { + if (!spawn_object_cmd_) { + spawn_object_cmd_ = true; + RCLCPP_INFO(this->get_logger(), "Spawn command is sent."); + } + } + } +} + +void ReactionAnalyzerNode::calculate_results( + const std::map & message_buffers, + const rclcpp::Time & spawn_cmd_time) +{ + // Map the reaction times w.r.t its header time to categorize it + PipelineMap pipeline_map; + + { + // set the spawn_cmd_time as the first reaction pair + ReactionPair reaction_pair; + reaction_pair.first = "spawn_cmd_time"; + reaction_pair.second.header.stamp = spawn_cmd_time; + reaction_pair.second.published_stamp = spawn_cmd_time; + pipeline_map[reaction_pair.second.header.stamp].emplace_back(reaction_pair); + } + + for (const auto & [key, variant] : message_buffers) { + ReactionPair reaction_pair; + if (auto * control_message = std::get_if(&variant)) { + if (control_message->second) { + reaction_pair.first = key; + reaction_pair.second = control_message->second.value(); + } + } else if (auto * general_message = std::get_if(&variant)) { + if (general_message->has_value()) { + reaction_pair.first = key; + reaction_pair.second = general_message->value(); + } + } + pipeline_map[reaction_pair.second.header.stamp].emplace_back(reaction_pair); + } + pipeline_map_vector_.emplace_back(pipeline_map); + test_iteration_count_++; +} + +void ReactionAnalyzerNode::init_analyzer_variables() +{ + entity_pose_ = create_entity_pose(node_params_.entity_params); + entity_debug_marker_ = create_polyhedron_marker(node_params_.entity_params); + goal_pose_.pose = pose_params_to_pose(node_params_.goal_pose); + + if (node_running_mode_ == RunningMode::PlanningControl) { + init_pose_.pose.pose = pose_params_to_pose(node_params_.initial_pose); + } +} + +void ReactionAnalyzerNode::init_test_env( + const LocalizationInitializationState::ConstSharedPtr & initialization_state_ptr, + const RouteState::ConstSharedPtr & route_state_ptr, + const OperationModeState::ConstSharedPtr & operation_mode_ptr, + const PoseStamped::ConstSharedPtr & ground_truth_pose_ptr, + const Odometry::ConstSharedPtr & odometry_ptr) +{ + const auto current_time = this->now(); + + // Initialize the test environment + constexpr double initialize_call_period = 1.0; // sec + if ( + !last_test_environment_init_request_time_ || + (current_time - last_test_environment_init_request_time_.value()).seconds() >= + initialize_call_period) { + last_test_environment_init_request_time_ = current_time; + + // Pose initialization of the ego + is_initialization_requested = !is_initialization_requested + ? init_ego(initialization_state_ptr, odometry_ptr, current_time) + : is_initialization_requested; + + if ( + is_initialization_requested && + initialization_state_ptr->state != LocalizationInitializationState::INITIALIZED) { + is_initialization_requested = false; + return; + } + + // Check is position initialized accurately, if node is running in perception_planning mode + if (node_running_mode_ == RunningMode::PerceptionPlanning) { + if (!check_ego_init_correctly(ground_truth_pose_ptr, odometry_ptr)) return; + } + + // Set route + is_route_set_ = !is_route_set_ ? set_route(route_state_ptr, current_time) : is_route_set_; + + if (!is_route_set_) { + return; + } + + // if node is running PlanningControl mode, change ego to Autonomous mode. + if (node_running_mode_ == RunningMode::PlanningControl) { + // change to autonomous + if (operation_mode_ptr && operation_mode_ptr->mode != OperationModeState::AUTONOMOUS) { + call_operation_mode_service_without_response(); + } + } + ego_initialized_ = true; + + const bool is_ready = + (is_initialization_requested && is_route_set_ && + (operation_mode_ptr->mode == OperationModeState::AUTONOMOUS || + node_running_mode_ == RunningMode::PerceptionPlanning)); + if (is_ready) { + test_environment_init_time_ = this->now(); + } + } +} + +void ReactionAnalyzerNode::call_operation_mode_service_without_response() +{ + auto req = std::make_shared(); + + RCLCPP_INFO(this->get_logger(), "client request"); + + if (!client_change_to_autonomous_->service_is_ready()) { + RCLCPP_INFO(this->get_logger(), "client is unavailable"); + return; + } + + client_change_to_autonomous_->async_send_request( + req, [this](typename rclcpp::Client::SharedFuture result) { + RCLCPP_INFO( + this->get_logger(), "Status: %d, %s", result.get()->status.code, + result.get()->status.message.c_str()); + }); +} + +bool ReactionAnalyzerNode::init_ego( + const LocalizationInitializationState::ConstSharedPtr & initialization_state_ptr, + const Odometry::ConstSharedPtr & odometry_ptr, const rclcpp::Time & current_time) +{ + // Pose initialization of the ego + if (initialization_state_ptr) { + if (node_running_mode_ == RunningMode::PlanningControl) { + // publish initial pose + init_pose_.header.stamp = current_time; + init_pose_.header.frame_id = "map"; + pub_initial_pose_->publish(init_pose_); + RCLCPP_WARN_ONCE(get_logger(), "Initialization position is published. Waiting for init..."); + } + // Wait until odometry_ptr is initialized + if (!odometry_ptr) { + RCLCPP_WARN_ONCE(get_logger(), "Odometry is not received. Waiting for odometry..."); + return false; + } + return true; + } + return false; +} + +bool ReactionAnalyzerNode::set_route( + const RouteState::ConstSharedPtr & route_state_ptr, const rclcpp::Time & current_time) +{ + if (route_state_ptr) { + if (route_state_ptr->state != RouteState::SET) { + // publish goal pose + goal_pose_.header.stamp = current_time; + goal_pose_.header.frame_id = "map"; + pub_goal_pose_->publish(goal_pose_); + return false; + } + return true; + } + return false; +} + +bool ReactionAnalyzerNode::check_ego_init_correctly( + const PoseStamped::ConstSharedPtr & ground_truth_pose_ptr, + const Odometry::ConstSharedPtr & odometry_ptr) +{ + if (!ground_truth_pose_ptr) { + RCLCPP_WARN( + get_logger(), "Ground truth pose is not received. Waiting for Ground truth pose..."); + return false; + } + if (!odometry_ptr) { + RCLCPP_WARN(get_logger(), "Odometry is not received. Waiting for odometry..."); + return false; + } + + constexpr double deviation_threshold = 0.1; + const auto deviation = + tier4_autoware_utils::calcPoseDeviation(ground_truth_pose_ptr->pose, odometry_ptr->pose.pose); + const bool is_position_initialized_correctly = deviation.longitudinal < deviation_threshold && + deviation.lateral < deviation_threshold && + deviation.yaw < deviation_threshold; + if (!is_position_initialized_correctly) { + RCLCPP_ERROR( + get_logger(), + "Deviation between ground truth position and ego position is high. Node is shutting " + "down. Longitudinal deviation: %f, Lateral deviation: %f, Yaw deviation: %f", + deviation.longitudinal, deviation.lateral, deviation.yaw); + rclcpp::shutdown(); + } + return true; +} + +void ReactionAnalyzerNode::reset() +{ + if (test_iteration_count_ >= node_params_.test_iteration) { + write_results(this, node_params_.output_file_path, node_running_mode_, pipeline_map_vector_); + RCLCPP_INFO(get_logger(), "%zu Tests are finished. Node shutting down.", test_iteration_count_); + rclcpp::shutdown(); + return; + } + // reset the variables + is_initialization_requested = false; + is_route_set_ = false; + test_environment_init_time_ = std::nullopt; + last_test_environment_init_request_time_ = std::nullopt; + spawn_object_cmd_ = false; + if (topic_publisher_ptr_) { + topic_publisher_ptr_->reset(); + } + std::lock_guard lock(mutex_); + spawn_cmd_time_ = std::nullopt; + subscriber_ptr_->reset(); + ego_initialized_ = false; + RCLCPP_INFO(this->get_logger(), "Test - %zu is done, resetting..", test_iteration_count_); +} +} // namespace reaction_analyzer + +#include + +#include + +RCLCPP_COMPONENTS_REGISTER_NODE(reaction_analyzer::ReactionAnalyzerNode) diff --git a/tools/reaction_analyzer/src/subscriber.cpp b/tools/reaction_analyzer/src/subscriber.cpp new file mode 100644 index 0000000000000..8c735c42b9cd5 --- /dev/null +++ b/tools/reaction_analyzer/src/subscriber.cpp @@ -0,0 +1,996 @@ +// 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 "subscriber.hpp" + +#include +#include +#include + +namespace reaction_analyzer::subscriber +{ + +SubscriberBase::SubscriberBase( + rclcpp::Node * node, Odometry::ConstSharedPtr & odometry, std::atomic & spawn_object_cmd, + const EntityParams & entity_params) +: node_(node), + odometry_(odometry), + spawn_object_cmd_(spawn_object_cmd), + entity_params_(entity_params) +{ + // init tf + tf_buffer_ = std::make_shared(node_->get_clock()); + tf_listener_ = std::make_shared(*tf_buffer_); + + // init reaction parameters and chain configuration + init_reaction_chains_and_params(); + init_subscribers(); +} + +void SubscriberBase::init_reaction_chains_and_params() +{ + // Init Chains: get the topic addresses and message types of the modules in chain + { + const auto param_key = std::string("subscriber.reaction_chain"); + const auto module_names = node_->list_parameters({param_key}, 3).prefixes; + for (const auto & module_name : module_names) { + const auto splitted_name = split(module_name, '.'); + TopicConfig tmp; + tmp.node_name = splitted_name.back(); + tmp.topic_address = node_->get_parameter(module_name + ".topic_name").as_string(); + tmp.time_debug_topic_address = + node_->get_parameter_or(module_name + ".time_debug_topic_name", std::string("")); + tmp.message_type = get_subscriber_message_type( + node_->get_parameter(module_name + ".message_type").as_string()); + if (tmp.message_type != SubscriberMessageType::UNKNOWN) { + chain_modules_.emplace_back(tmp); + } else { + RCLCPP_WARN( + node_->get_logger(), "Unknown message type for module name: %s, skipping..", + tmp.node_name.c_str()); + } + } + } + + // Init Params: get the parameters for the reaction functions + { + const auto param_key = std::string("subscriber.reaction_params"); + const auto module_names = node_->list_parameters({param_key}, 3).prefixes; + for (const auto & module_name : module_names) { + const auto splitted_name = split(module_name, '.'); + const auto type = get_reaction_type(splitted_name.back()); + switch (type) { + case ReactionType::FIRST_BRAKE: { + reaction_params_.first_brake_params.debug_control_commands = + node_->get_parameter(module_name + ".debug_control_commands").as_bool(); + reaction_params_.first_brake_params.control_cmd_buffer_time_interval = + node_->get_parameter(module_name + ".control_cmd_buffer_time_interval").as_double(); + reaction_params_.first_brake_params.min_number_descending_order_control_cmd = + node_->get_parameter(module_name + ".min_number_descending_order_control_cmd").as_int(); + reaction_params_.first_brake_params.min_jerk_for_brake_cmd = + node_->get_parameter(module_name + ".min_jerk_for_brake_cmd").as_double(); + RCLCPP_INFO_ONCE( + node_->get_logger(), + "First brake parameters are set: debug_control_commands %s, " + "control_cmd_buffer_time_interval %f, min_number_descending_order_control_cmd %zu, " + "min_jerk_for_brake_cmd %f", + reaction_params_.first_brake_params.debug_control_commands ? "true" : "false", + reaction_params_.first_brake_params.control_cmd_buffer_time_interval, + reaction_params_.first_brake_params.min_number_descending_order_control_cmd, + reaction_params_.first_brake_params.min_jerk_for_brake_cmd); + break; + } + case ReactionType::SEARCH_ZERO_VEL: { + reaction_params_.search_zero_vel_params.max_looking_distance = + node_->get_parameter(module_name + ".max_looking_distance").as_double(); + RCLCPP_INFO_ONCE( + node_->get_logger(), "Search Zero Vel parameters are set: max_looking_distance %f", + reaction_params_.search_zero_vel_params.max_looking_distance); + break; + } + case ReactionType::SEARCH_ENTITY: { + reaction_params_.search_entity_params.search_radius_offset = + node_->get_parameter(module_name + ".search_radius_offset").as_double(); + RCLCPP_INFO_ONCE( + node_->get_logger(), "Search Entity parameters are set: search_radius_offset %f", + reaction_params_.search_entity_params.search_radius_offset); + break; + } + default: + RCLCPP_WARN( + node_->get_logger(), "Unknown reaction type for module name: %s, skipping..", + splitted_name.back().c_str()); + break; + } + } + } + + // Init variables + { + entity_pose_ = create_entity_pose(entity_params_); + entity_search_radius_ = calculate_entity_search_radius(entity_params_) + + reaction_params_.search_entity_params.search_radius_offset; + } +} + +bool SubscriberBase::init_subscribers() +{ + if (chain_modules_.empty()) { + RCLCPP_ERROR(node_->get_logger(), "No module to initialize subscribers, failed."); + return false; + } + + for (const auto & module : chain_modules_) { + if (module.message_type == SubscriberMessageType::UNKNOWN) { + RCLCPP_WARN( + node_->get_logger(), "Unknown message type for topic_config name: %s, skipping..", + module.node_name.c_str()); + } + auto subscriber_var = get_subscriber_variable(module); + if (!subscriber_var) { + RCLCPP_ERROR( + node_->get_logger(), "Failed to initialize subscriber for module name: %s", + module.node_name.c_str()); + return false; + } + subscriber_variables_map_[module.node_name] = std::move(subscriber_var.value()); + } + return true; +} + +std::optional> SubscriberBase::get_message_buffers_map() +{ + std::lock_guard lock(mutex_); + if (message_buffers_.empty()) { + RCLCPP_ERROR(node_->get_logger(), "No message buffers are initialized."); + return std::nullopt; + } + + // Check all reacted or not + bool all_reacted = true; + for (const auto & [key, variant] : message_buffers_) { + if (auto * control_message = std::get_if(&variant)) { + if (!control_message->second) { + RCLCPP_WARN_THROTTLE( + node_->get_logger(), *node_->get_clock(), 1000, "Waiting for %s to react", key.c_str()); + all_reacted = false; + } + } else if (auto * general_message = std::get_if(&variant)) { + if (!general_message->has_value()) { + RCLCPP_WARN_THROTTLE( + node_->get_logger(), *node_->get_clock(), 1000, "Waiting for %s to react", key.c_str()); + all_reacted = false; + } + } + } + if (!all_reacted) { + return std::nullopt; + } + return message_buffers_; +} + +void SubscriberBase::reset() +{ + std::lock_guard lock(mutex_); + message_buffers_.clear(); +} + +// Callbacks + +void SubscriberBase::on_control_command( + const std::string & node_name, const AckermannControlCommand::ConstSharedPtr & msg_ptr) +{ + std::lock_guard lock(mutex_); + auto & variant = message_buffers_[node_name]; + if (!std::holds_alternative(variant)) { + ControlCommandBuffer buffer(std::vector{*msg_ptr}, std::nullopt); + variant = buffer; + } + auto & cmd_buffer = std::get(variant); + if (cmd_buffer.second) { + // reacted + return; + } + set_control_command_to_buffer(cmd_buffer.first, *msg_ptr); + if (!spawn_object_cmd_) return; + + const auto brake_idx = find_first_brake_idx(cmd_buffer.first); + if (brake_idx) { + const auto brake_cmd = cmd_buffer.first.at(brake_idx.value()); + + // TODO(brkay54): update here if message_filters package add support for the messages which + // does not have header + const auto & subscriber_variant = + std::get>(subscriber_variables_map_[node_name]); + + // check if the cache was initialized or not, if there is, use it to set the published time + if (subscriber_variant.cache_) { + // use cache to get the published time + const auto published_time_vec = + subscriber_variant.cache_->getSurroundingInterval(brake_cmd.stamp, node_->now()); + if (!published_time_vec.empty()) { + for (const auto & published_time : published_time_vec) { + if (published_time->header.stamp == brake_cmd.stamp) { + cmd_buffer.second = *published_time; + RCLCPP_INFO(node_->get_logger(), "%s reacted with published time", node_name.c_str()); + return; + } + } + RCLCPP_ERROR( + node_->get_logger(), "Published time couldn't found for the node: %s", node_name.c_str()); + + } else { + RCLCPP_ERROR( + node_->get_logger(), "Published time vector is empty for the node: %s", + node_name.c_str()); + } + } else { + cmd_buffer.second->header.stamp = brake_cmd.stamp; + cmd_buffer.second->published_stamp = brake_cmd.stamp; + RCLCPP_INFO(node_->get_logger(), "%s reacted without published time", node_name.c_str()); + } + } +} + +void SubscriberBase::on_trajectory( + const std::string & node_name, const Trajectory::ConstSharedPtr & msg_ptr) +{ + mutex_.lock(); + auto variant = message_buffers_[node_name]; + const auto current_odometry_ptr = odometry_; + if (!std::holds_alternative(variant)) { + MessageBuffer buffer(std::nullopt); + variant = buffer; + message_buffers_[node_name] = variant; + } + mutex_.unlock(); + + if (!current_odometry_ptr || !spawn_object_cmd_ || std::get(variant).has_value()) { + return; + } + + const auto nearest_seg_idx = motion_utils::findNearestSegmentIndex( + msg_ptr->points, current_odometry_ptr->pose.pose.position); + + const auto nearest_objects_seg_idx = + motion_utils::findNearestIndex(msg_ptr->points, entity_pose_.position); + + const auto zero_vel_idx = motion_utils::searchZeroVelocityIndex( + msg_ptr->points, nearest_seg_idx, nearest_objects_seg_idx); + + if (zero_vel_idx) { + RCLCPP_INFO(node_->get_logger(), "%s reacted without published time", node_name.c_str()); + // set header time + auto & buffer = std::get(variant); + buffer->header.stamp = msg_ptr->header.stamp; + buffer->published_stamp = msg_ptr->header.stamp; + mutex_.lock(); + message_buffers_[node_name] = variant; + mutex_.unlock(); + } +} + +void SubscriberBase::on_trajectory( + const std::string & node_name, const Trajectory::ConstSharedPtr & msg_ptr, + const PublishedTime::ConstSharedPtr & published_time_ptr) +{ + mutex_.lock(); + auto variant = message_buffers_[node_name]; + const auto current_odometry_ptr = odometry_; + if (!std::holds_alternative(variant)) { + MessageBuffer buffer(std::nullopt); + variant = buffer; + message_buffers_[node_name] = variant; + } + mutex_.unlock(); + + if (!current_odometry_ptr || !spawn_object_cmd_ || std::get(variant).has_value()) { + return; + } + + const auto nearest_seg_idx = motion_utils::findNearestSegmentIndex( + msg_ptr->points, current_odometry_ptr->pose.pose.position); + + // find the target index which we will search for zero velocity + auto tmp_target_idx = get_index_after_distance( + *msg_ptr, nearest_seg_idx, reaction_params_.search_zero_vel_params.max_looking_distance); + if (tmp_target_idx == msg_ptr->points.size() - 1) { + tmp_target_idx = msg_ptr->points.size() - 2; // Last trajectory points might be zero velocity + } + const auto target_idx = tmp_target_idx; + const auto zero_vel_idx = + motion_utils::searchZeroVelocityIndex(msg_ptr->points, nearest_seg_idx, target_idx); + + if (zero_vel_idx) { + RCLCPP_INFO(node_->get_logger(), "%s reacted with published time", node_name.c_str()); + // set published time + auto & buffer = std::get(variant); + buffer = *published_time_ptr; + mutex_.lock(); + message_buffers_[node_name] = variant; + mutex_.unlock(); + } +} + +void SubscriberBase::on_pointcloud( + const std::string & node_name, const PointCloud2::ConstSharedPtr & msg_ptr) +{ + mutex_.lock(); + auto variant = message_buffers_[node_name]; + if (!std::holds_alternative(variant)) { + MessageBuffer buffer(std::nullopt); + variant = buffer; + message_buffers_[node_name] = variant; + } + mutex_.unlock(); + + if (!spawn_object_cmd_ || std::get(variant).has_value()) { + return; + } + + // transform pointcloud + geometry_msgs::msg::TransformStamped transform_stamped{}; + try { + transform_stamped = tf_buffer_->lookupTransform( + "map", msg_ptr->header.frame_id, node_->now(), rclcpp::Duration::from_seconds(0.1)); + } catch (tf2::TransformException & ex) { + RCLCPP_ERROR_STREAM( + node_->get_logger(), + "Failed to look up transform from " << msg_ptr->header.frame_id << " to map"); + return; + } + + // transform by using eigen matrix + PointCloud2 transformed_points{}; + const Eigen::Matrix4f affine_matrix = + tf2::transformToEigen(transform_stamped.transform).matrix().cast(); + pcl_ros::transformPointCloud(affine_matrix, *msg_ptr, transformed_points); + + pcl::PointCloud pcl_pointcloud; + pcl::fromROSMsg(transformed_points, pcl_pointcloud); + + if (search_pointcloud_near_pose(pcl_pointcloud, entity_pose_, entity_search_radius_)) { + RCLCPP_INFO(node_->get_logger(), "%s reacted without published time", node_name.c_str()); + // set header time + auto & buffer = std::get(variant); + buffer->header.stamp = msg_ptr->header.stamp; + buffer->published_stamp = msg_ptr->header.stamp; + mutex_.lock(); + message_buffers_[node_name] = variant; + mutex_.unlock(); + } +} +void SubscriberBase::on_pointcloud( + const std::string & node_name, const PointCloud2::ConstSharedPtr & msg_ptr, + const PublishedTime::ConstSharedPtr & published_time_ptr) +{ + mutex_.lock(); + auto variant = message_buffers_[node_name]; + if (!std::holds_alternative(variant)) { + MessageBuffer buffer(std::nullopt); + variant = buffer; + message_buffers_[node_name] = variant; + } + mutex_.unlock(); + + if (!spawn_object_cmd_ || std::get(variant).has_value()) { + return; + } + + // transform pointcloud + geometry_msgs::msg::TransformStamped transform_stamped{}; + try { + transform_stamped = tf_buffer_->lookupTransform( + "map", msg_ptr->header.frame_id, node_->now(), rclcpp::Duration::from_seconds(0.1)); + } catch (tf2::TransformException & ex) { + RCLCPP_ERROR_STREAM( + node_->get_logger(), + "Failed to look up transform from " << msg_ptr->header.frame_id << " to map"); + return; + } + + // transform by using eigen matrix + PointCloud2 transformed_points{}; + const Eigen::Matrix4f affine_matrix = + tf2::transformToEigen(transform_stamped.transform).matrix().cast(); + pcl_ros::transformPointCloud(affine_matrix, *msg_ptr, transformed_points); + + pcl::PointCloud pcl_pointcloud; + pcl::fromROSMsg(transformed_points, pcl_pointcloud); + + if (search_pointcloud_near_pose(pcl_pointcloud, entity_pose_, entity_search_radius_)) { + RCLCPP_INFO(node_->get_logger(), "%s reacted with published time", node_name.c_str()); + // set published time + auto & buffer = std::get(variant); + buffer = *published_time_ptr; + mutex_.lock(); + message_buffers_[node_name] = variant; + mutex_.unlock(); + } +} +void SubscriberBase::on_predicted_objects( + const std::string & node_name, const PredictedObjects::ConstSharedPtr & msg_ptr) +{ + mutex_.lock(); + auto variant = message_buffers_[node_name]; + if (!std::holds_alternative(variant)) { + MessageBuffer buffer(std::nullopt); + variant = buffer; + message_buffers_[node_name] = variant; + } + mutex_.unlock(); + + if ( + !spawn_object_cmd_ || msg_ptr->objects.empty() || + std::get(variant).has_value()) { + return; + } + + if (search_predicted_objects_near_pose(*msg_ptr, entity_pose_, entity_search_radius_)) { + RCLCPP_INFO(node_->get_logger(), "%s reacted without published time", node_name.c_str()); + // set header time + auto & buffer = std::get(variant); + buffer->header.stamp = msg_ptr->header.stamp; + buffer->published_stamp = msg_ptr->header.stamp; + mutex_.lock(); + message_buffers_[node_name] = variant; + mutex_.unlock(); + } +} + +void SubscriberBase::on_predicted_objects( + const std::string & node_name, const PredictedObjects::ConstSharedPtr & msg_ptr, + const PublishedTime::ConstSharedPtr & published_time_ptr) +{ + mutex_.lock(); + auto variant = message_buffers_[node_name]; + if (!std::holds_alternative(variant)) { + MessageBuffer buffer(std::nullopt); + variant = buffer; + message_buffers_[node_name] = variant; + } + mutex_.unlock(); + + if ( + !spawn_object_cmd_ || msg_ptr->objects.empty() || + std::get(variant).has_value()) { + return; + } + + if (search_predicted_objects_near_pose(*msg_ptr, entity_pose_, entity_search_radius_)) { + RCLCPP_INFO(node_->get_logger(), "%s reacted with published time", node_name.c_str()); + // set published time + auto & buffer = std::get(variant); + buffer = *published_time_ptr; + mutex_.lock(); + message_buffers_[node_name] = variant; + mutex_.unlock(); + } +} + +void SubscriberBase::on_detected_objects( + const std::string & node_name, const DetectedObjects::ConstSharedPtr & msg_ptr) +{ + mutex_.lock(); + auto variant = message_buffers_[node_name]; + if (!std::holds_alternative(variant)) { + MessageBuffer buffer(std::nullopt); + variant = buffer; + message_buffers_[node_name] = variant; + } + mutex_.unlock(); + if ( + !spawn_object_cmd_ || msg_ptr->objects.empty() || + std::get(variant).has_value()) { + return; + } + + // transform objects + geometry_msgs::msg::TransformStamped transform_stamped{}; + try { + transform_stamped = tf_buffer_->lookupTransform( + "map", msg_ptr->header.frame_id, node_->now(), rclcpp::Duration::from_seconds(0.1)); + } catch (tf2::TransformException & ex) { + RCLCPP_ERROR_STREAM( + node_->get_logger(), + "Failed to look up transform from " << msg_ptr->header.frame_id << " to map"); + return; + } + + DetectedObjects output_objs; + output_objs = *msg_ptr; + for (auto & obj : output_objs.objects) { + geometry_msgs::msg::PoseStamped output_stamped; + geometry_msgs::msg::PoseStamped input_stamped; + input_stamped.pose = obj.kinematics.pose_with_covariance.pose; + tf2::doTransform(input_stamped, output_stamped, transform_stamped); + obj.kinematics.pose_with_covariance.pose = output_stamped.pose; + } + if (search_detected_objects_near_pose(output_objs, entity_pose_, entity_search_radius_)) { + RCLCPP_INFO(node_->get_logger(), "%s reacted without published time", node_name.c_str()); + // set header time + auto & buffer = std::get(variant); + buffer->header.stamp = msg_ptr->header.stamp; + buffer->published_stamp = msg_ptr->header.stamp; + mutex_.lock(); + message_buffers_[node_name] = variant; + mutex_.unlock(); + } +} + +void SubscriberBase::on_detected_objects( + const std::string & node_name, const DetectedObjects::ConstSharedPtr & msg_ptr, + const PublishedTime::ConstSharedPtr & published_time_ptr) +{ + mutex_.lock(); + auto variant = message_buffers_[node_name]; + if (!std::holds_alternative(variant)) { + MessageBuffer buffer(std::nullopt); + variant = buffer; + message_buffers_[node_name] = variant; + } + mutex_.unlock(); + if ( + !spawn_object_cmd_ || msg_ptr->objects.empty() || + std::get(variant).has_value()) { + return; + } + + // transform objects + geometry_msgs::msg::TransformStamped transform_stamped{}; + try { + transform_stamped = tf_buffer_->lookupTransform( + "map", msg_ptr->header.frame_id, node_->now(), rclcpp::Duration::from_seconds(0.1)); + } catch (tf2::TransformException & ex) { + RCLCPP_ERROR_STREAM( + node_->get_logger(), + "Failed to look up transform from " << msg_ptr->header.frame_id << " to map"); + return; + } + + DetectedObjects output_objs; + output_objs = *msg_ptr; + for (auto & obj : output_objs.objects) { + geometry_msgs::msg::PoseStamped output_stamped; + geometry_msgs::msg::PoseStamped input_stamped; + input_stamped.pose = obj.kinematics.pose_with_covariance.pose; + tf2::doTransform(input_stamped, output_stamped, transform_stamped); + obj.kinematics.pose_with_covariance.pose = output_stamped.pose; + } + if (search_detected_objects_near_pose(output_objs, entity_pose_, entity_search_radius_)) { + RCLCPP_INFO(node_->get_logger(), "%s reacted with published time", node_name.c_str()); + // set published time + auto & buffer = std::get(variant); + buffer = *published_time_ptr; + mutex_.lock(); + message_buffers_[node_name] = variant; + mutex_.unlock(); + } +} + +void SubscriberBase::on_tracked_objects( + const std::string & node_name, const TrackedObjects::ConstSharedPtr & msg_ptr) +{ + mutex_.lock(); + auto variant = message_buffers_[node_name]; + if (!std::holds_alternative(variant)) { + MessageBuffer buffer(std::nullopt); + variant = buffer; + message_buffers_[node_name] = variant; + } + mutex_.unlock(); + if ( + !spawn_object_cmd_ || msg_ptr->objects.empty() || + std::get(variant).has_value()) { + return; + } + + if (search_tracked_objects_near_pose(*msg_ptr, entity_pose_, entity_search_radius_)) { + mutex_.lock(); + message_buffers_[node_name] = variant; + mutex_.unlock(); + } +} + +void SubscriberBase::on_tracked_objects( + const std::string & node_name, const TrackedObjects::ConstSharedPtr & msg_ptr, + const PublishedTime::ConstSharedPtr & published_time_ptr) +{ + mutex_.lock(); + auto variant = message_buffers_[node_name]; + if (!std::holds_alternative(variant)) { + MessageBuffer buffer(std::nullopt); + variant = buffer; + message_buffers_[node_name] = variant; + } + mutex_.unlock(); + if ( + !spawn_object_cmd_ || msg_ptr->objects.empty() || + std::get(variant).has_value()) { + return; + } + + if (search_tracked_objects_near_pose(*msg_ptr, entity_pose_, entity_search_radius_)) { + RCLCPP_INFO(node_->get_logger(), "%s reacted with published time", node_name.c_str()); + // set published time + auto & buffer = std::get(variant); + buffer = *published_time_ptr; + mutex_.lock(); + message_buffers_[node_name] = variant; + mutex_.unlock(); + } +} + +std::optional SubscriberBase::get_subscriber_variable( + const TopicConfig & topic_config) +{ + switch (topic_config.message_type) { + case SubscriberMessageType::ACKERMANN_CONTROL_COMMAND: { + SubscriberVariables subscriber_variable; + + if (!topic_config.time_debug_topic_address.empty()) { + // If not empty, user should define a time debug topic + // NOTE: Because message_filters package does not support the messages without headers, we + // can not use the synchronizer. After we reacted, we are going to use the cache + // of the both PublishedTime and AckermannControlCommand subscribers to find the messages + // which have same header time. + + std::function callback = + [this, topic_config](const AckermannControlCommand::ConstSharedPtr & ptr) { + this->on_control_command(topic_config.node_name, ptr); + }; + subscriber_variable.sub1_ = + std::make_unique>( + node_, topic_config.topic_address, rclcpp::QoS(1).get_rmw_qos_profile(), + create_subscription_options(node_)); + + subscriber_variable.sub1_->registerCallback(std::bind(callback, std::placeholders::_1)); + + subscriber_variable.sub2_ = std::make_unique>( + node_, topic_config.time_debug_topic_address, rclcpp::QoS(1).get_rmw_qos_profile(), + create_subscription_options(node_)); + constexpr int cache_size = 5; + subscriber_variable.cache_ = std::make_unique>( + *subscriber_variable.sub2_, cache_size); + + } else { + std::function callback = + [this, topic_config](const AckermannControlCommand::ConstSharedPtr & ptr) { + this->on_control_command(topic_config.node_name, ptr); + }; + + subscriber_variable.sub1_ = + std::make_unique>( + node_, topic_config.topic_address, rclcpp::QoS(1).get_rmw_qos_profile(), + create_subscription_options(node_)); + + subscriber_variable.sub1_->registerCallback(std::bind(callback, std::placeholders::_1)); + RCLCPP_WARN( + node_->get_logger(), + "PublishedTime will not be used for node name: %s. Header timestamp will be used for " + "calculations", + topic_config.node_name.c_str()); + } + return subscriber_variable; + } + case SubscriberMessageType::TRAJECTORY: { + SubscriberVariables subscriber_variable; + + if (!topic_config.time_debug_topic_address.empty()) { + std::function + callback = [this, topic_config]( + const Trajectory::ConstSharedPtr & ptr, + const PublishedTime::ConstSharedPtr & published_time_ptr) { + this->on_trajectory(topic_config.node_name, ptr, published_time_ptr); + }; + + subscriber_variable.sub1_ = std::make_unique>( + node_, topic_config.topic_address, rclcpp::QoS(1).get_rmw_qos_profile(), + create_subscription_options(node_)); + subscriber_variable.sub2_ = std::make_unique>( + node_, topic_config.time_debug_topic_address, rclcpp::QoS(1).get_rmw_qos_profile(), + create_subscription_options(node_)); + + subscriber_variable.synchronizer_ = std::make_unique< + message_filters::Synchronizer::ExactTimePolicy>>( + SubscriberVariables::ExactTimePolicy(10), *subscriber_variable.sub1_, + *subscriber_variable.sub2_); + + subscriber_variable.synchronizer_->registerCallback( + std::bind(callback, std::placeholders::_1, std::placeholders::_2)); + + } else { + std::function callback = + [this, topic_config](const Trajectory::ConstSharedPtr & msg) { + this->on_trajectory(topic_config.node_name, msg); + }; + subscriber_variable.sub1_ = std::make_unique>( + node_, topic_config.topic_address, rclcpp::QoS(1).get_rmw_qos_profile(), + create_subscription_options(node_)); + + subscriber_variable.sub1_->registerCallback(std::bind(callback, std::placeholders::_1)); + RCLCPP_WARN( + node_->get_logger(), + "PublishedTime will not be used for node name: %s. Header timestamp will be used for " + "calculations", + topic_config.node_name.c_str()); + } + return subscriber_variable; + } + case SubscriberMessageType::POINTCLOUD2: { + SubscriberVariables subscriber_variable; + + if (!topic_config.time_debug_topic_address.empty()) { + std::function + callback = [this, topic_config]( + const PointCloud2::ConstSharedPtr & ptr, + const PublishedTime::ConstSharedPtr & published_time_ptr) { + this->on_pointcloud(topic_config.node_name, ptr, published_time_ptr); + }; + + subscriber_variable.sub1_ = std::make_unique>( + node_, topic_config.topic_address, rclcpp::SensorDataQoS().get_rmw_qos_profile(), + create_subscription_options(node_)); + subscriber_variable.sub2_ = std::make_unique>( + node_, topic_config.time_debug_topic_address, rclcpp::QoS(1).get_rmw_qos_profile(), + create_subscription_options(node_)); + + subscriber_variable.synchronizer_ = std::make_unique< + message_filters::Synchronizer::ExactTimePolicy>>( + SubscriberVariables::ExactTimePolicy(10), *subscriber_variable.sub1_, + *subscriber_variable.sub2_); + + subscriber_variable.synchronizer_->registerCallback( + std::bind(callback, std::placeholders::_1, std::placeholders::_2)); + + } else { + std::function callback = + [this, topic_config](const PointCloud2::ConstSharedPtr & msg) { + this->on_pointcloud(topic_config.node_name, msg); + }; + subscriber_variable.sub1_ = std::make_unique>( + node_, topic_config.topic_address, rclcpp::QoS(1).get_rmw_qos_profile(), + create_subscription_options(node_)); + + subscriber_variable.sub1_->registerCallback(std::bind(callback, std::placeholders::_1)); + RCLCPP_WARN( + node_->get_logger(), + "PublishedTime will not be used for node name: %s. Header timestamp will be used for " + "calculations", + topic_config.node_name.c_str()); + } + return subscriber_variable; + } + case SubscriberMessageType::PREDICTED_OBJECTS: { + SubscriberVariables subscriber_variable; + + if (!topic_config.time_debug_topic_address.empty()) { + std::function + callback = [this, topic_config]( + const PredictedObjects::ConstSharedPtr & ptr, + const PublishedTime::ConstSharedPtr & published_time_ptr) { + this->on_predicted_objects(topic_config.node_name, ptr, published_time_ptr); + }; + subscriber_variable.sub1_ = std::make_unique>( + node_, topic_config.topic_address, rclcpp::QoS(1).get_rmw_qos_profile(), + create_subscription_options(node_)); + subscriber_variable.sub2_ = std::make_unique>( + node_, topic_config.time_debug_topic_address, rclcpp::QoS(1).get_rmw_qos_profile(), + create_subscription_options(node_)); + + subscriber_variable.synchronizer_ = std::make_unique< + message_filters::Synchronizer::ExactTimePolicy>>( + SubscriberVariables::ExactTimePolicy(10), *subscriber_variable.sub1_, + *subscriber_variable.sub2_); + + subscriber_variable.synchronizer_->registerCallback( + std::bind(callback, std::placeholders::_1, std::placeholders::_2)); + + } else { + std::function callback = + [this, topic_config](const PredictedObjects::ConstSharedPtr & msg) { + this->on_predicted_objects(topic_config.node_name, msg); + }; + subscriber_variable.sub1_ = std::make_unique>( + node_, topic_config.topic_address, rclcpp::QoS(1).get_rmw_qos_profile(), + create_subscription_options(node_)); + + subscriber_variable.sub1_->registerCallback(std::bind(callback, std::placeholders::_1)); + RCLCPP_WARN( + node_->get_logger(), + "PublishedTime will not be used for node name: %s. Header timestamp will be used for " + "calculations", + topic_config.node_name.c_str()); + } + return subscriber_variable; + } + case SubscriberMessageType::DETECTED_OBJECTS: { + SubscriberVariables subscriber_variable; + + if (!topic_config.time_debug_topic_address.empty()) { + std::function + callback = [this, topic_config]( + const DetectedObjects::ConstSharedPtr & ptr, + const PublishedTime::ConstSharedPtr & published_time_ptr) { + this->on_detected_objects(topic_config.node_name, ptr, published_time_ptr); + }; + + subscriber_variable.sub1_ = std::make_unique>( + node_, topic_config.topic_address, rclcpp::QoS(1).get_rmw_qos_profile(), + create_subscription_options(node_)); + subscriber_variable.sub2_ = std::make_unique>( + node_, topic_config.time_debug_topic_address, rclcpp::QoS(1).get_rmw_qos_profile(), + create_subscription_options(node_)); + + subscriber_variable.synchronizer_ = std::make_unique< + message_filters::Synchronizer::ExactTimePolicy>>( + SubscriberVariables::ExactTimePolicy(10), *subscriber_variable.sub1_, + *subscriber_variable.sub2_); + + subscriber_variable.synchronizer_->registerCallback( + std::bind(callback, std::placeholders::_1, std::placeholders::_2)); + + } else { + std::function callback = + [this, topic_config](const DetectedObjects::ConstSharedPtr & msg) { + this->on_detected_objects(topic_config.node_name, msg); + }; + subscriber_variable.sub1_ = std::make_unique>( + node_, topic_config.topic_address, rclcpp::QoS(1).get_rmw_qos_profile(), + create_subscription_options(node_)); + + subscriber_variable.sub1_->registerCallback(std::bind(callback, std::placeholders::_1)); + RCLCPP_WARN( + node_->get_logger(), + "PublishedTime will not be used for node name: %s. Header timestamp will be used for " + "calculations", + topic_config.node_name.c_str()); + } + return subscriber_variable; + } + case SubscriberMessageType::TRACKED_OBJECTS: { + SubscriberVariables subscriber_variable; + if (!topic_config.time_debug_topic_address.empty()) { + std::function + callback = [this, topic_config]( + const TrackedObjects::ConstSharedPtr & ptr, + const PublishedTime::ConstSharedPtr & published_time_ptr) { + this->on_tracked_objects(topic_config.node_name, ptr, published_time_ptr); + }; + + subscriber_variable.sub1_ = std::make_unique>( + node_, topic_config.topic_address, rclcpp::QoS(1).get_rmw_qos_profile(), + create_subscription_options(node_)); + subscriber_variable.sub2_ = std::make_unique>( + node_, topic_config.time_debug_topic_address, rclcpp::QoS(1).get_rmw_qos_profile(), + create_subscription_options(node_)); + + subscriber_variable.synchronizer_ = std::make_unique< + message_filters::Synchronizer::ExactTimePolicy>>( + SubscriberVariables::ExactTimePolicy(10), *subscriber_variable.sub1_, + *subscriber_variable.sub2_); + + subscriber_variable.synchronizer_->registerCallback( + std::bind(callback, std::placeholders::_1, std::placeholders::_2)); + + } else { + std::function callback = + [this, topic_config](const TrackedObjects::ConstSharedPtr & msg) { + this->on_tracked_objects(topic_config.node_name, msg); + }; + subscriber_variable.sub1_ = std::make_unique>( + node_, topic_config.topic_address, rclcpp::QoS(1).get_rmw_qos_profile(), + create_subscription_options(node_)); + + subscriber_variable.sub1_->registerCallback(std::bind(callback, std::placeholders::_1)); + RCLCPP_WARN( + node_->get_logger(), + "PublishedTime will not be used for node name: %s. Header timestamp will be used for " + "calculations", + topic_config.node_name.c_str()); + } + return subscriber_variable; + } + default: + RCLCPP_WARN( + node_->get_logger(), "Unknown message type for topic_config name: %s, skipping..", + topic_config.node_name.c_str()); + return std::nullopt; + } +} + +std::optional SubscriberBase::find_first_brake_idx( + const std::vector & cmd_array) +{ + if ( + cmd_array.size() < + reaction_params_.first_brake_params.min_number_descending_order_control_cmd) { + RCLCPP_WARN_ONCE( + node_->get_logger(), + "Control command buffer size is less than the minimum required size for first brake check"); + return {}; + } + + for (size_t i = 0; + i < cmd_array.size() - + reaction_params_.first_brake_params.min_number_descending_order_control_cmd + 1; + ++i) { + size_t decreased_cmd_counter = 1; // because # of the decreased cmd = iteration + 1 + for (size_t j = i; j < cmd_array.size() - 1; ++j) { + const auto & cmd_first = cmd_array.at(j).longitudinal; + const auto & cmd_second = cmd_array.at(j + 1).longitudinal; + constexpr double jerk_time_epsilon = 0.001; + const auto jerk = + abs(cmd_second.acceleration - cmd_first.acceleration) / + std::max( + (rclcpp::Time(cmd_second.stamp) - rclcpp::Time(cmd_first.stamp)).seconds(), + jerk_time_epsilon); + + if ( + (cmd_second.acceleration < cmd_first.acceleration) && + (jerk > reaction_params_.first_brake_params.min_jerk_for_brake_cmd)) { + decreased_cmd_counter++; + } else { + break; + } + } + if ( + decreased_cmd_counter < + static_cast( + reaction_params_.first_brake_params.min_number_descending_order_control_cmd)) + continue; + if (reaction_params_.first_brake_params.debug_control_commands) { + std::stringstream ss; + + // debug print to show the first brake command in the all control commands + for (size_t k = 0; k < cmd_array.size(); ++k) { + if (k == i + 1) { + ss << "First Brake(" << cmd_array.at(k).longitudinal.acceleration << ") "; + } else { + ss << cmd_array.at(k).longitudinal.acceleration << " "; + } + } + + RCLCPP_INFO(node_->get_logger(), "%s", ss.str().c_str()); + } + return i + 1; + } + return {}; +} + +void SubscriberBase::set_control_command_to_buffer( + std::vector & buffer, const AckermannControlCommand & cmd) const +{ + const auto last_cmd_time = cmd.stamp; + if (!buffer.empty()) { + for (auto itr = buffer.begin(); itr != buffer.end();) { + const auto expired = (rclcpp::Time(last_cmd_time) - rclcpp::Time(itr->stamp)).seconds() > + reaction_params_.first_brake_params.control_cmd_buffer_time_interval; + + if (expired) { + itr = buffer.erase(itr); + continue; + } + + itr++; + } + } + buffer.emplace_back(cmd); +} +} // namespace reaction_analyzer::subscriber diff --git a/tools/reaction_analyzer/src/topic_publisher.cpp b/tools/reaction_analyzer/src/topic_publisher.cpp new file mode 100644 index 0000000000000..8a66bf9e33911 --- /dev/null +++ b/tools/reaction_analyzer/src/topic_publisher.cpp @@ -0,0 +1,536 @@ +// 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 "topic_publisher.hpp" + +#include +#include + +namespace reaction_analyzer::topic_publisher +{ + +TopicPublisher::TopicPublisher( + rclcpp::Node * node, std::atomic & spawn_object_cmd, std::atomic & ego_initialized, + std::optional & spawn_cmd_time, const RunningMode & node_running_mode, + const EntityParams & entity_params) +: node_(node), + node_running_mode_(node_running_mode), + spawn_object_cmd_(spawn_object_cmd), + ego_initialized_(ego_initialized), + entity_params_(entity_params), + spawn_cmd_time_(spawn_cmd_time) +{ + if (node_running_mode_ == RunningMode::PerceptionPlanning) { + // get perception_planning mode parameters + topic_publisher_params_.path_bag_with_object = + node_->get_parameter("topic_publisher.path_bag_with_object").as_string(); + topic_publisher_params_.path_bag_without_object = + node_->get_parameter("topic_publisher.path_bag_without_object").as_string(); + topic_publisher_params_.pointcloud_publisher_type = + node_->get_parameter("topic_publisher.pointcloud_publisher.pointcloud_publisher_type") + .as_string(); + topic_publisher_params_.pointcloud_publisher_period = + node_->get_parameter("topic_publisher.pointcloud_publisher.pointcloud_publisher_period") + .as_double(); + topic_publisher_params_.publish_only_pointcloud_with_object = + node_ + ->get_parameter("topic_publisher.pointcloud_publisher.publish_only_pointcloud_with_object") + .as_bool(); + + // set pointcloud publisher type + if (topic_publisher_params_.pointcloud_publisher_type == "sync_header_sync_publish") { + pointcloud_publisher_type_ = PointcloudPublisherType::SYNC_HEADER_SYNC_PUBLISHER; + } else if (topic_publisher_params_.pointcloud_publisher_type == "async_header_sync_publish") { + pointcloud_publisher_type_ = PointcloudPublisherType::ASYNC_HEADER_SYNC_PUBLISHER; + } else if (topic_publisher_params_.pointcloud_publisher_type == "async_publish") { + pointcloud_publisher_type_ = PointcloudPublisherType::ASYNC_PUBLISHER; + } else { + RCLCPP_ERROR(node_->get_logger(), "Invalid pointcloud_publisher_type"); + rclcpp::shutdown(); + return; + } + + // Init the publishers which will read the messages from the rosbag + init_rosbag_publishers(); + } else if (node_running_mode_ == RunningMode::PlanningControl) { + // init tf + tf_buffer_ = std::make_shared(node_->get_clock()); + tf_listener_ = std::make_shared(*tf_buffer_); + + // get parameters + topic_publisher_params_.dummy_perception_publisher_period = + node_->get_parameter("topic_publisher.dummy_perception_publisher_period").as_double(); + topic_publisher_params_.spawned_pointcloud_sampling_distance = + node_->get_parameter("topic_publisher.spawned_pointcloud_sampling_distance").as_double(); + + // init the messages that will be published to spawn the object + entity_pointcloud_ptr_ = create_entity_pointcloud_ptr( + entity_params_, topic_publisher_params_.spawned_pointcloud_sampling_distance); + predicted_objects_ptr_ = create_entity_predicted_objects_ptr(entity_params_); + + // init the publishers + pub_pointcloud_ = + node_->create_publisher("output/pointcloud", rclcpp::SensorDataQoS()); + pub_predicted_objects_ = + node_->create_publisher("output/objects", rclcpp::QoS(1)); + + // init dummy perception publisher + const auto period_ns = std::chrono::duration_cast( + std::chrono::duration(topic_publisher_params_.dummy_perception_publisher_period)); + + dummy_perception_timer_ = rclcpp::create_timer( + node_, node_->get_clock(), period_ns, + std::bind(&TopicPublisher::dummy_perception_publisher, this)); + } else { + RCLCPP_ERROR(node_->get_logger(), "Invalid running mode"); + rclcpp::shutdown(); + return; + } +} + +void TopicPublisher::pointcloud_messages_sync_publisher(const PointcloudPublisherType type) +{ + const auto current_time = node_->now(); + const bool is_object_spawned = spawn_object_cmd_; + + switch (type) { + case PointcloudPublisherType::SYNC_HEADER_SYNC_PUBLISHER: { + PublisherVarAccessor accessor; + for (const auto & publisher_var_pair : lidar_pub_variable_pair_map_) { + accessor.publish_with_current_time( + *publisher_var_pair.second.first, current_time, + topic_publisher_params_.publish_only_pointcloud_with_object || is_object_spawned); + accessor.publish_with_current_time( + *publisher_var_pair.second.second, current_time, + topic_publisher_params_.publish_only_pointcloud_with_object || is_object_spawned); + } + if (is_object_spawned && !is_object_spawned_message_published_) { + is_object_spawned_message_published_ = true; + mutex_.lock(); + spawn_cmd_time_ = current_time; + mutex_.unlock(); + } + break; + } + case PointcloudPublisherType::ASYNC_HEADER_SYNC_PUBLISHER: { + PublisherVarAccessor accessor; + const auto period_pointcloud_ns = std::chrono::duration_cast( + std::chrono::duration(topic_publisher_params_.pointcloud_publisher_period)); + const auto phase_dif = period_pointcloud_ns / lidar_pub_variable_pair_map_.size(); + + size_t counter = 0; + for (const auto & publisher_var_pair : lidar_pub_variable_pair_map_) { + const auto header_time = + current_time - std::chrono::nanoseconds(counter * phase_dif.count()); + accessor.publish_with_current_time( + *publisher_var_pair.second.first, header_time, + topic_publisher_params_.publish_only_pointcloud_with_object || is_object_spawned); + accessor.publish_with_current_time( + *publisher_var_pair.second.second, header_time, + topic_publisher_params_.publish_only_pointcloud_with_object || is_object_spawned); + counter++; + } + if (is_object_spawned && !is_object_spawned_message_published_) { + is_object_spawned_message_published_ = true; + mutex_.lock(); + spawn_cmd_time_ = current_time; + mutex_.unlock(); + } + break; + } + default: + break; + } +} + +void TopicPublisher::pointcloud_messages_async_publisher( + const std::pair< + std::shared_ptr>, + std::shared_ptr>> & lidar_output_pair_) +{ + PublisherVarAccessor accessor; + const auto current_time = node_->now(); + const bool is_object_spawned = spawn_object_cmd_; + accessor.publish_with_current_time( + *lidar_output_pair_.first, current_time, + topic_publisher_params_.publish_only_pointcloud_with_object || is_object_spawned); + accessor.publish_with_current_time( + *lidar_output_pair_.second, current_time, + topic_publisher_params_.publish_only_pointcloud_with_object || is_object_spawned); + + if (is_object_spawned && !is_object_spawned_message_published_) { + is_object_spawned_message_published_ = true; + mutex_.lock(); + spawn_cmd_time_ = current_time; + mutex_.unlock(); + } +} + +void TopicPublisher::generic_message_publisher(const std::string & topic_name) +{ + PublisherVarAccessor accessor; + const bool is_object_spawned = spawn_object_cmd_; + const auto current_time = node_->now(); + const auto & publisher_variant = topic_publisher_map_[topic_name]; + + std::visit( + [&](const auto & var) { + accessor.publish_with_current_time(var, current_time, is_object_spawned); + }, + publisher_variant); +} + +void TopicPublisher::dummy_perception_publisher() +{ + if (!ego_initialized_) { + return; // do not publish anything if ego is not initialized + } + if (!spawn_object_cmd_) { + // do not spawn it, send empty pointcloud + pcl::PointCloud pcl_empty; + PointCloud2 empty_pointcloud; + PredictedObjects empty_predicted_objects; + pcl::toROSMsg(pcl_empty, empty_pointcloud); + + const auto current_time = node_->now(); + empty_pointcloud.header.frame_id = "base_link"; + empty_pointcloud.header.stamp = current_time; + + empty_predicted_objects.header.frame_id = "map"; + empty_predicted_objects.header.stamp = current_time; + + pub_pointcloud_->publish(empty_pointcloud); + pub_predicted_objects_->publish(empty_predicted_objects); + } else { + // transform pointcloud + geometry_msgs::msg::TransformStamped transform_stamped{}; + try { + transform_stamped = tf_buffer_->lookupTransform( + "base_link", "map", node_->now(), rclcpp::Duration::from_seconds(0.1)); + } catch (tf2::TransformException & ex) { + RCLCPP_ERROR_STREAM(node_->get_logger(), "Failed to look up transform from map to base_link"); + return; + } + + // transform by using eigen matrix + PointCloud2 transformed_points{}; + const Eigen::Matrix4f affine_matrix = + tf2::transformToEigen(transform_stamped.transform).matrix().cast(); + pcl_ros::transformPointCloud(affine_matrix, *entity_pointcloud_ptr_, transformed_points); + const auto current_time = node_->now(); + + transformed_points.header.frame_id = "base_link"; + transformed_points.header.stamp = current_time; + + predicted_objects_ptr_->header.frame_id = "map"; + predicted_objects_ptr_->header.stamp = current_time; + + pub_pointcloud_->publish(transformed_points); + pub_predicted_objects_->publish(*predicted_objects_ptr_); + if (!is_object_spawned_message_published_) { + mutex_.lock(); + spawn_cmd_time_ = current_time; + mutex_.unlock(); + is_object_spawned_message_published_ = true; + } + } +} + +void TopicPublisher::reset() +{ + is_object_spawned_message_published_ = false; +} + +void TopicPublisher::init_rosbag_publishers() +{ + // read messages without object + init_rosbag_publisher_buffer(topic_publisher_params_.path_bag_without_object, true); + + // read messages with object + init_rosbag_publisher_buffer(topic_publisher_params_.path_bag_with_object, false); + + // before create publishers and timers, check all the messages are correctly initialized with + // their conjugate messages. + if (check_publishers_initialized_correctly()) { + RCLCPP_INFO(node_->get_logger(), "Messages are initialized correctly"); + } else { + RCLCPP_ERROR(node_->get_logger(), "Messages are not initialized correctly"); + rclcpp::shutdown(); + } + set_publishers_and_timers_to_variable(); +} + +template +void TopicPublisher::set_message( + const std::string & topic_name, const rosbag2_storage::SerializedBagMessage & bag_message, + const bool is_empty_area_message) +{ + rclcpp::Serialization serialization; + rclcpp::SerializedMessage extracted_serialized_msg(*bag_message.serialized_data); + + // Deserialize the message + auto deserialized_message = std::make_shared(); + serialization.deserialize_message(&extracted_serialized_msg, &*deserialized_message); + auto & publisher_variant = topic_publisher_map_[topic_name]; + + if (!std::holds_alternative>(publisher_variant)) { + publisher_variant = PublisherVariables{}; + } + + auto & publisher_variable = std::get>(publisher_variant); + + if (is_empty_area_message) { + if (!publisher_variable.empty_area_message) { + publisher_variable.empty_area_message = deserialized_message; + } + } else { + if (!publisher_variable.object_spawned_message) { + publisher_variable.object_spawned_message = deserialized_message; + } + } +} + +void TopicPublisher::set_period(const std::map> & time_map) +{ + for (auto & topic_pair : time_map) { + auto timestamps_tmp = topic_pair.second; + + // Sort the timestamps + std::sort(timestamps_tmp.begin(), timestamps_tmp.end()); + + // Then proceed with the frequency calculation + std::string topic_name = topic_pair.first; + if (timestamps_tmp.size() > 1) { + int64_t total_time_diff_ns = 0; + + // Accumulate the differences in nanoseconds + for (size_t i = 1; i < timestamps_tmp.size(); ++i) { + total_time_diff_ns += (timestamps_tmp[i] - timestamps_tmp[i - 1]).nanoseconds(); + } + + // Conversion to std::chrono::milliseconds + auto total_duration_ns = std::chrono::nanoseconds(total_time_diff_ns); + auto period_ms = std::chrono::duration_cast(total_duration_ns) / + (timestamps_tmp.size() - 1); + + PublisherVariablesVariant & publisher_variant = topic_publisher_map_[topic_name]; + PublisherVarAccessor accessor; + + std::visit([&](auto & var) { accessor.set_period(var, period_ms); }, publisher_variant); + } + } +} + +void TopicPublisher::set_publishers_and_timers_to_variable() +{ + std::map> + pointcloud_variables_map; // temp map for pointcloud publishers + + // initialize timers and message publishers except pointcloud messages + for (auto & [topic_name, variant] : topic_publisher_map_) { + PublisherVarAccessor accessor; + const auto & topic_ref = topic_name; + const auto period_ns = std::chrono::duration( + std::visit([&](const auto & var) { return accessor.get_period(var); }, variant)); + + // Dynamically create the correct publisher type based on the topic + std::visit( + [&](auto & var) { + using MessageType = typename decltype(var.empty_area_message)::element_type; + + if constexpr ( + std::is_same_v || + std::is_same_v || + std::is_same_v) { + var.publisher = node_->create_publisher(topic_ref, rclcpp::SensorDataQoS()); + } else { + // For other message types, use the QoS setting depth of 1 + var.publisher = node_->create_publisher(topic_ref, rclcpp::QoS(1)); + } + }, + variant); + + // Conditionally create the timer based on the message type, if message type is not + // PointCloud2 + std::visit( + [&](auto & var) { + using MessageType = typename decltype(var.empty_area_message)::element_type; + + if constexpr (!std::is_same_v) { + var.timer = node_->create_wall_timer( + period_ns, [this, topic_ref]() { this->generic_message_publisher(topic_ref); }); + } else { + // For PointCloud2, Store the variables in a temporary map + pointcloud_variables_map[topic_ref] = var; + } + }, + variant); + } + + // To be able to publish pointcloud messages with async, I need to create a timer for each lidar + // output. So different operations are needed for pointcloud messages. + set_timers_for_pointcloud_msgs(pointcloud_variables_map); +} + +void TopicPublisher::set_timers_for_pointcloud_msgs( + const std::map> & pointcloud_variables_map) +{ + // Set the point cloud publisher timers + if (pointcloud_variables_map.empty()) { + RCLCPP_ERROR(node_->get_logger(), "No pointcloud publishers found!"); + rclcpp::shutdown(); + } + + // Arrange the PointCloud2 variables w.r.t. the lidars' name + for (auto & [topic_name, pointcloud_variant] : pointcloud_variables_map) { + const auto lidar_name = split(topic_name, '/').at(3); + + if (lidar_pub_variable_pair_map_.find(lidar_name) == lidar_pub_variable_pair_map_.end()) { + lidar_pub_variable_pair_map_[lidar_name] = std::make_pair( + std::make_shared>(pointcloud_variant), nullptr); + } else { + if (lidar_pub_variable_pair_map_[lidar_name].second) { + RCLCPP_ERROR_STREAM( + node_->get_logger(), + "Lidar name: " << lidar_name << " is already used by another pointcloud publisher"); + rclcpp::shutdown(); + } + lidar_pub_variable_pair_map_[lidar_name].second = + std::make_shared>(pointcloud_variant); + } + } + + // Create the timer(s) to publish PointCloud2 Messages + const auto period_pointcloud_ns = std::chrono::duration_cast( + std::chrono::duration(topic_publisher_params_.pointcloud_publisher_period)); + + if (pointcloud_publisher_type_ != PointcloudPublisherType::ASYNC_PUBLISHER) { + // Create 1 timer to publish all PointCloud2 messages + pointcloud_sync_publish_timer_ = node_->create_wall_timer(period_pointcloud_ns, [this]() { + this->pointcloud_messages_sync_publisher(this->pointcloud_publisher_type_); + }); + } else { + // Create multiple timers which will run with a phase difference + const auto phase_dif = period_pointcloud_ns / lidar_pub_variable_pair_map_.size(); + + // Create a timer to create phase difference bw timers which will be created for each lidar + // topics + auto one_shot_timer = node_->create_wall_timer(phase_dif, [this, period_pointcloud_ns]() { + for (const auto & publisher_var_pair : lidar_pub_variable_pair_map_) { + const auto & lidar_name = publisher_var_pair.first; + const auto & publisher_var = publisher_var_pair.second; + if ( + pointcloud_publish_timers_map_.find(lidar_name) == pointcloud_publish_timers_map_.end()) { + auto periodic_timer = node_->create_wall_timer( + period_pointcloud_ns, + [this, publisher_var]() { this->pointcloud_messages_async_publisher(publisher_var); }); + pointcloud_publish_timers_map_[lidar_name] = periodic_timer; + return; + } + } + one_shot_timer_shared_ptr_->cancel(); + }); + one_shot_timer_shared_ptr_ = one_shot_timer; + } +} + +bool TopicPublisher::check_publishers_initialized_correctly() +{ + // check messages are correctly initialized or not from rosbags + for (const auto & [topic_name, variant] : topic_publisher_map_) { + PublisherVarAccessor accessor; + auto empty_area_message = + std::visit([&](const auto & var) { return accessor.get_empty_area_message(var); }, variant); + auto object_spawned_message = std::visit( + [&](const auto & var) { return accessor.get_object_spawned_message(var); }, variant); + + if (!empty_area_message) { + RCLCPP_ERROR_STREAM( + node_->get_logger(), + "Empty area message couldn't found in the topic named: " << topic_name); + return false; + } + if (!object_spawned_message) { + RCLCPP_ERROR_STREAM( + node_->get_logger(), + "Object spawned message couldn't found in the topic named: " << topic_name); + return false; + } + } + return true; +} + +void TopicPublisher::init_rosbag_publisher_buffer( + const std::string & bag_path, const bool is_empty_area_message) +{ + rosbag2_cpp::Reader reader; + + try { + reader.open(bag_path); + } catch (const std::exception & e) { + RCLCPP_ERROR_STREAM(node_->get_logger(), "Error opening bag file: " << e.what()); + rclcpp::shutdown(); + return; + } + + const auto & topics = reader.get_metadata().topics_with_message_count; + + while (reader.has_next()) { + auto bag_message = reader.read_next(); + const auto current_topic = bag_message->topic_name; + + const auto message_type = get_publisher_message_type_for_topic(topics, current_topic); + + if (message_type == PublisherMessageType::UNKNOWN) { + continue; + } + if (message_type == PublisherMessageType::CAMERA_INFO) { + set_message(current_topic, *bag_message, is_empty_area_message); + } else if (message_type == PublisherMessageType::IMAGE) { + set_message(current_topic, *bag_message, is_empty_area_message); + } else if (message_type == PublisherMessageType::POINTCLOUD2) { + set_message(current_topic, *bag_message, is_empty_area_message); + } else if (message_type == PublisherMessageType::POSE_WITH_COVARIANCE_STAMPED) { + set_message( + current_topic, *bag_message, is_empty_area_message); + } else if (message_type == PublisherMessageType::POSE_STAMPED) { + set_message( + current_topic, *bag_message, is_empty_area_message); + } else if (message_type == PublisherMessageType::ODOMETRY) { + set_message(current_topic, *bag_message, is_empty_area_message); + } else if (message_type == PublisherMessageType::IMU) { + set_message(current_topic, *bag_message, is_empty_area_message); + } else if (message_type == PublisherMessageType::CONTROL_MODE_REPORT) { + set_message( + current_topic, *bag_message, is_empty_area_message); + } else if (message_type == PublisherMessageType::GEAR_REPORT) { + set_message( + current_topic, *bag_message, is_empty_area_message); + } else if (message_type == PublisherMessageType::HAZARD_LIGHTS_REPORT) { + set_message( + current_topic, *bag_message, is_empty_area_message); + } else if (message_type == PublisherMessageType::STEERING_REPORT) { + set_message( + current_topic, *bag_message, is_empty_area_message); + } else if (message_type == PublisherMessageType::TURN_INDICATORS_REPORT) { + set_message( + current_topic, *bag_message, is_empty_area_message); + } else if (message_type == PublisherMessageType::VELOCITY_REPORT) { + set_message( + current_topic, *bag_message, is_empty_area_message); + } + } + reader.close(); +} +} // namespace reaction_analyzer::topic_publisher diff --git a/tools/reaction_analyzer/src/utils.cpp b/tools/reaction_analyzer/src/utils.cpp new file mode 100644 index 0000000000000..4a6110322440e --- /dev/null +++ b/tools/reaction_analyzer/src/utils.cpp @@ -0,0 +1,589 @@ +// 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 "utils.hpp" + +namespace reaction_analyzer +{ +SubscriberMessageType get_subscriber_message_type(const std::string & message_type) +{ + if (message_type == "autoware_auto_control_msgs/msg/AckermannControlCommand") { + return SubscriberMessageType::ACKERMANN_CONTROL_COMMAND; + } + if (message_type == "autoware_auto_planning_msgs/msg/Trajectory") { + return SubscriberMessageType::TRAJECTORY; + } + if (message_type == "sensor_msgs/msg/PointCloud2") { + return SubscriberMessageType::POINTCLOUD2; + } + if (message_type == "autoware_auto_perception_msgs/msg/PredictedObjects") { + return SubscriberMessageType::PREDICTED_OBJECTS; + } + if (message_type == "autoware_auto_perception_msgs/msg/DetectedObjects") { + return SubscriberMessageType::DETECTED_OBJECTS; + } + if (message_type == "autoware_auto_perception_msgs/msg/TrackedObjects") { + return SubscriberMessageType::TRACKED_OBJECTS; + } + return SubscriberMessageType::UNKNOWN; +} + +PublisherMessageType get_publisher_message_type(const std::string & message_type) +{ + if (message_type == "sensor_msgs/msg/PointCloud2") { + return PublisherMessageType::POINTCLOUD2; + } + if (message_type == "sensor_msgs/msg/CameraInfo") { + return PublisherMessageType::CAMERA_INFO; + } + if (message_type == "sensor_msgs/msg/Image") { + return PublisherMessageType::IMAGE; + } + if (message_type == "geometry_msgs/msg/PoseWithCovarianceStamped") { + return PublisherMessageType::POSE_WITH_COVARIANCE_STAMPED; + } + if (message_type == "geometry_msgs/msg/PoseStamped") { + return PublisherMessageType::POSE_STAMPED; + } + if (message_type == "nav_msgs/msg/Odometry") { + return PublisherMessageType::ODOMETRY; + } + if (message_type == "sensor_msgs/msg/Imu") { + return PublisherMessageType::IMU; + } + if (message_type == "autoware_auto_vehicle_msgs/msg/ControlModeReport") { + return PublisherMessageType::CONTROL_MODE_REPORT; + } + if (message_type == "autoware_auto_vehicle_msgs/msg/GearReport") { + return PublisherMessageType::GEAR_REPORT; + } + if (message_type == "autoware_auto_vehicle_msgs/msg/HazardLightsReport") { + return PublisherMessageType::HAZARD_LIGHTS_REPORT; + } + if (message_type == "autoware_auto_vehicle_msgs/msg/SteeringReport") { + return PublisherMessageType::STEERING_REPORT; + } + if (message_type == "autoware_auto_vehicle_msgs/msg/TurnIndicatorsReport") { + return PublisherMessageType::TURN_INDICATORS_REPORT; + } + if (message_type == "autoware_auto_vehicle_msgs/msg/VelocityReport") { + return PublisherMessageType::VELOCITY_REPORT; + } + return PublisherMessageType::UNKNOWN; +} + +PublisherMessageType get_publisher_message_type_for_topic( + const std::vector & topics, const std::string & topic_name) +{ + auto it = std::find_if(topics.begin(), topics.end(), [&topic_name](const auto & topic) { + return topic.topic_metadata.name == topic_name; + }); + if (it != topics.end()) { + return get_publisher_message_type(it->topic_metadata.type); // Return the message type if found + } + return PublisherMessageType::UNKNOWN; +} + +ReactionType get_reaction_type(const std::string & reaction_type) +{ + if (reaction_type == "first_brake_params") { + return ReactionType::FIRST_BRAKE; + } + if (reaction_type == "search_zero_vel_params") { + return ReactionType::SEARCH_ZERO_VEL; + } + if (reaction_type == "search_entity_params") { + return ReactionType::SEARCH_ENTITY; + } + return ReactionType::UNKNOWN; +} + +rclcpp::SubscriptionOptions create_subscription_options(rclcpp::Node * node) +{ + rclcpp::CallbackGroup::SharedPtr callback_group = + node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + + auto sub_opt = rclcpp::SubscriptionOptions(); + sub_opt.callback_group = callback_group; + + return sub_opt; +} + +visualization_msgs::msg::Marker create_polyhedron_marker(const EntityParams & params) +{ + visualization_msgs::msg::Marker marker; + marker.header.frame_id = "map"; + marker.header.stamp = rclcpp::Time(0); + marker.ns = "entity"; + marker.id = 0; + marker.type = visualization_msgs::msg::Marker::LINE_STRIP; + marker.action = visualization_msgs::msg::Marker::ADD; + + marker.pose.position.x = params.x; + marker.pose.position.y = params.y; + marker.pose.position.z = params.z; + + tf2::Quaternion quaternion; + quaternion.setRPY( + tier4_autoware_utils::deg2rad(params.roll), tier4_autoware_utils::deg2rad(params.pitch), + tier4_autoware_utils::deg2rad(params.yaw)); + marker.pose.orientation = tf2::toMsg(quaternion); + + marker.scale.x = 0.1; // Line width + + marker.color.a = 1.0; // Alpha + marker.color.r = 1.0; + marker.color.g = 0.0; + marker.color.b = 0.0; + + // Define the 8 corners of the polyhedron + geometry_msgs::msg::Point p1, p2, p3, p4, p5, p6, p7, p8; + + p1.x = params.x_l / 2.0; + p1.y = params.y_l / 2.0; + p1.z = params.z_l / 2.0; + p2.x = -params.x_l / 2.0; + p2.y = params.y_l / 2.0; + p2.z = params.z_l / 2.0; + p3.x = -params.x_l / 2.0; + p3.y = -params.y_l / 2.0; + p3.z = params.z_l / 2.0; + p4.x = params.x_l / 2.0; + p4.y = -params.y_l / 2.0; + p4.z = params.z_l / 2.0; + p5.x = params.x_l / 2.0; + p5.y = params.y_l / 2.0; + p5.z = -params.z_l / 2.0; + p6.x = -params.x_l / 2.0; + p6.y = params.y_l / 2.0; + p6.z = -params.z_l / 2.0; + p7.x = -params.x_l / 2.0; + p7.y = -params.y_l / 2.0; + p7.z = -params.z_l / 2.0; + p8.x = params.x_l / 2.0; + p8.y = -params.y_l / 2.0; + p8.z = -params.z_l / 2.0; + + // Add points to the marker + marker.points.push_back(p1); + marker.points.push_back(p2); + marker.points.push_back(p3); + marker.points.push_back(p4); + marker.points.push_back(p1); + + marker.points.push_back(p5); + marker.points.push_back(p6); + marker.points.push_back(p7); + marker.points.push_back(p8); + marker.points.push_back(p5); + + marker.points.push_back(p1); + marker.points.push_back(p5); + marker.points.push_back(p6); + marker.points.push_back(p2); + marker.points.push_back(p3); + marker.points.push_back(p7); + marker.points.push_back(p4); + marker.points.push_back(p8); + + return marker; +} + +std::vector split(const std::string & str, char delimiter) +{ + std::vector elements; + std::stringstream ss(str); + std::string item; + while (std::getline(ss, item, delimiter)) { + elements.push_back(item); + } + return elements; +} + +bool does_folder_exist(const std::string & path) +{ + return std::filesystem::exists(path) && std::filesystem::is_directory(path); +} + +size_t get_index_after_distance( + const Trajectory & traj, const size_t curr_id, const double distance) +{ + const TrajectoryPoint & curr_p = traj.points.at(curr_id); + + size_t target_id = curr_id; + double current_distance = 0.0; + for (size_t traj_id = curr_id + 1; traj_id < traj.points.size(); ++traj_id) { + current_distance = tier4_autoware_utils::calcDistance3d(traj.points.at(traj_id), curr_p); + if (current_distance >= distance) { + break; + } + target_id = traj_id; + } + return target_id; +} + +double calculate_time_diff_ms(const rclcpp::Time & start, const rclcpp::Time & end) +{ + const auto duration = end - start; + + const auto duration_ns = duration.to_chrono(); + return static_cast(duration_ns.count()) / 1e6; +} + +TimestampedReactionPairsVector convert_pipeline_map_to_sorted_vector( + const PipelineMap & pipelineMap) +{ + std::vector>> sorted_vector; + + for (const auto & entry : pipelineMap) { + auto sorted_reactions = entry.second; + // Sort the vector of ReactionPair based on the published stamp + std::sort( + sorted_reactions.begin(), sorted_reactions.end(), + [](const ReactionPair & a, const ReactionPair & b) { + return rclcpp::Time(a.second.published_stamp) < rclcpp::Time(b.second.published_stamp); + }); + + // Add to the vector as a tuple + sorted_vector.emplace_back(std::make_tuple(entry.first, sorted_reactions)); + } + + // Sort the vector of tuples by rclcpp::Time + std::sort(sorted_vector.begin(), sorted_vector.end(), [](const auto & a, const auto & b) { + return std::get<0>(a) < std::get<0>(b); + }); + + return sorted_vector; +} + +unique_identifier_msgs::msg::UUID generate_uuid_msg(const std::string & input) +{ + static auto generate_uuid = boost::uuids::name_generator(boost::uuids::random_generator()()); + const auto uuid = generate_uuid(input); + + unique_identifier_msgs::msg::UUID uuid_msg; + std::copy(uuid.begin(), uuid.end(), uuid_msg.uuid.begin()); + return uuid_msg; +} + +geometry_msgs::msg::Pose create_entity_pose(const EntityParams & entity_params) +{ + geometry_msgs::msg::Pose entity_pose; + entity_pose.position.x = entity_params.x; + entity_pose.position.y = entity_params.y; + entity_pose.position.z = entity_params.z; + + tf2::Quaternion entity_q_orientation; + entity_q_orientation.setRPY( + tier4_autoware_utils::deg2rad(entity_params.roll), + tier4_autoware_utils::deg2rad(entity_params.pitch), + tier4_autoware_utils::deg2rad(entity_params.yaw)); + entity_pose.orientation = tf2::toMsg(entity_q_orientation); + return entity_pose; +} + +geometry_msgs::msg::Pose pose_params_to_pose(const PoseParams & pose_params) +{ + geometry_msgs::msg::Pose pose; + pose.position.x = pose_params.x; + pose.position.y = pose_params.y; + pose.position.z = pose_params.z; + + tf2::Quaternion pose_q_orientation; + pose_q_orientation.setRPY( + tier4_autoware_utils::deg2rad(pose_params.roll), + tier4_autoware_utils::deg2rad(pose_params.pitch), + tier4_autoware_utils::deg2rad(pose_params.yaw)); + pose.orientation = tf2::toMsg(pose_q_orientation); + return pose; +} + +PointCloud2::SharedPtr create_entity_pointcloud_ptr( + const EntityParams & entity_params, const double pointcloud_sampling_distance) +{ + pcl::PointCloud point_cloud; + tf2::Quaternion entity_q_orientation; + + entity_q_orientation.setRPY( + tier4_autoware_utils::deg2rad(entity_params.roll), + tier4_autoware_utils::deg2rad(entity_params.pitch), + tier4_autoware_utils::deg2rad(entity_params.yaw)); + tf2::Transform tf(entity_q_orientation); + const auto origin = tf2::Vector3(entity_params.x, entity_params.y, entity_params.z); + tf.setOrigin(origin); + + const double it_x = entity_params.x_l / pointcloud_sampling_distance; + const double it_y = entity_params.y_l / pointcloud_sampling_distance; + const double it_z = entity_params.z_l / pointcloud_sampling_distance; + + // Sample the box and rotate + for (int i = 0; i <= it_z; ++i) { + for (int j = 0; j <= it_y; ++j) { + for (int k = 0; k <= it_x; ++k) { + const double p_x = -entity_params.x_l / 2 + k * pointcloud_sampling_distance; + const double p_y = -entity_params.y_l / 2 + j * pointcloud_sampling_distance; + const double p_z = -entity_params.z_l / 2 + i * pointcloud_sampling_distance; + const auto tmp = tf2::Vector3(p_x, p_y, p_z); + tf2::Vector3 data_out = tf * tmp; + point_cloud.emplace_back(pcl::PointXYZ( + static_cast(data_out.x()), static_cast(data_out.y()), + static_cast(data_out.z()))); + } + } + } + PointCloud2::SharedPtr entity_pointcloud_ptr; + entity_pointcloud_ptr = std::make_shared(); + pcl::toROSMsg(point_cloud, *entity_pointcloud_ptr); + return entity_pointcloud_ptr; +} + +PredictedObjects::SharedPtr create_entity_predicted_objects_ptr(const EntityParams & entity_params) +{ + unique_identifier_msgs::msg::UUID uuid_msg; + + PredictedObject obj; + const auto entity_pose = create_entity_pose(entity_params); + geometry_msgs::msg::Vector3 dimension; + dimension.set__x(entity_params.x_l); + dimension.set__y(entity_params.y_l); + dimension.set__z(entity_params.z_l); + obj.shape.set__dimensions(dimension); + + obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; + obj.existence_probability = 1.0; + obj.kinematics.initial_pose_with_covariance.pose = entity_pose; + + autoware_auto_perception_msgs::msg::PredictedPath path; + path.confidence = 1.0; + path.path.emplace_back(entity_pose); + obj.kinematics.predicted_paths.emplace_back(path); + + autoware_auto_perception_msgs::msg::ObjectClassification classification; + classification.label = autoware_auto_perception_msgs::msg::ObjectClassification::CAR; + classification.probability = 1.0; + obj.classification.emplace_back(classification); + obj.set__object_id(generate_uuid_msg("test_obstacle")); + + PredictedObjects pred_objects; + pred_objects.objects.emplace_back(obj); + return std::make_shared(pred_objects); +} + +double calculate_entity_search_radius(const EntityParams & entity_params) +{ + return std::sqrt( + std::pow(entity_params.x_l, 2) + std::pow(entity_params.y_l, 2) + + std::pow(entity_params.z_l, 2)) / + 2.0; +} + +bool search_pointcloud_near_pose( + const pcl::PointCloud & pcl_pointcloud, const geometry_msgs::msg::Pose & pose, + const double search_radius) +{ + return std::any_of( + pcl_pointcloud.points.begin(), pcl_pointcloud.points.end(), + [pose, search_radius](const auto & point) { + return tier4_autoware_utils::calcDistance3d(pose.position, point) <= search_radius; + }); +} + +bool search_predicted_objects_near_pose( + const PredictedObjects & predicted_objects, const geometry_msgs::msg::Pose & pose, + const double search_radius) +{ + return std::any_of( + predicted_objects.objects.begin(), predicted_objects.objects.end(), + [pose, search_radius](const PredictedObject & object) { + return tier4_autoware_utils::calcDistance3d( + pose.position, object.kinematics.initial_pose_with_covariance.pose.position) <= + search_radius; + }); + ; +} + +bool search_detected_objects_near_pose( + const DetectedObjects & detected_objects, const geometry_msgs::msg::Pose & pose, + const double search_radius) +{ + return std::any_of( + detected_objects.objects.begin(), detected_objects.objects.end(), + [pose, search_radius](const DetectedObject & object) { + return tier4_autoware_utils::calcDistance3d( + pose.position, object.kinematics.pose_with_covariance.pose.position) <= + search_radius; + }); +} + +bool search_tracked_objects_near_pose( + const TrackedObjects & tracked_objects, const geometry_msgs::msg::Pose & pose, + const double search_radius) +{ + return std::any_of( + tracked_objects.objects.begin(), tracked_objects.objects.end(), + [pose, search_radius](const TrackedObject & object) { + return tier4_autoware_utils::calcDistance3d( + pose.position, object.kinematics.pose_with_covariance.pose.position) <= + search_radius; + }); +} + +LatencyStats calculate_statistics(const std::vector & latency_vec) +{ + LatencyStats stats{0.0, 0.0, 0.0, 0.0, 0.0}; + stats.max = *max_element(latency_vec.begin(), latency_vec.end()); + stats.min = *min_element(latency_vec.begin(), latency_vec.end()); + + const double sum = std::accumulate(latency_vec.begin(), latency_vec.end(), 0.0); + stats.mean = sum / static_cast(latency_vec.size()); + + std::vector sorted_latencies = latency_vec; + std::sort(sorted_latencies.begin(), sorted_latencies.end()); + stats.median = sorted_latencies.size() % 2 == 0 + ? (sorted_latencies[sorted_latencies.size() / 2 - 1] + + sorted_latencies[sorted_latencies.size() / 2]) / + 2 + : sorted_latencies[sorted_latencies.size() / 2]; + + const double sq_sum = + std::inner_product(latency_vec.begin(), latency_vec.end(), latency_vec.begin(), 0.0); + stats.std_dev = + std::sqrt(sq_sum / static_cast(latency_vec.size()) - stats.mean * stats.mean); + return stats; +} + +void write_results( + rclcpp::Node * node, const std::string & output_file_path, const RunningMode & node_running_mode, + const std::vector & pipeline_map_vector) +{ + // create csv file + auto now = std::chrono::system_clock::now(); + auto in_time_t = std::chrono::system_clock::to_time_t(now); + + std::stringstream ss; + ss << output_file_path; + if (!output_file_path.empty() && output_file_path.back() != '/') { + ss << "/"; // Ensure the path ends with a slash + } + if (node_running_mode == RunningMode::PlanningControl) { + ss << "planning_control-"; + } else { + ss << "perception_planning-"; + } + + ss << std::put_time(std::localtime(&in_time_t), "%Y-%m-%d-%H-%M-%S"); + ss << "-reaction-results.csv"; + + // open file + std::ofstream file(ss.str()); + + // Check if the file was opened successfully + if (!file.is_open()) { + RCLCPP_ERROR_ONCE(node->get_logger(), "Failed to open file: %s", ss.str().c_str()); + return; + } + + // tmp map to store latency results for statistics + std::map>> tmp_latency_map; + + size_t test_count = 0; + for (const auto & pipeline_map : pipeline_map_vector) { + test_count++; + // convert pipeline_map to vector of tuples + file << "Test " << test_count << "\n"; + const auto sorted_results_vector = convert_pipeline_map_to_sorted_vector(pipeline_map); + const auto spawn_cmd_time = std::get<0>(*sorted_results_vector.begin()); + + for (size_t i = 0; i < sorted_results_vector.size(); ++i) { + const auto & [pipeline_header_time, pipeline_reactions] = sorted_results_vector[i]; + + // total time pipeline lasts + file << "Pipeline - " << i << ","; + + // pipeline nodes + for (const auto & [node_name, reaction] : pipeline_reactions) { + file << node_name << ","; + } + + file << "\nNode - Pipeline - Total Latency [ms],"; + + for (size_t j = 0; j < pipeline_reactions.size(); ++j) { + const auto & reaction = pipeline_reactions[j].second; + const auto & node_name = pipeline_reactions[j].first; + if (j == 0) { + const auto node_latency = + calculate_time_diff_ms(reaction.header.stamp, reaction.published_stamp); + const auto pipeline_latency = + calculate_time_diff_ms(pipeline_header_time, reaction.published_stamp); + const auto total_latency = + calculate_time_diff_ms(spawn_cmd_time, reaction.published_stamp); + file << node_latency << " - " << pipeline_latency << " - " << total_latency << ","; + tmp_latency_map[node_name].emplace_back( + std::make_tuple(node_latency, pipeline_latency, total_latency)); + } else { + const auto & prev_reaction = pipeline_reactions[j - 1].second; + const auto node_latency = + calculate_time_diff_ms(prev_reaction.published_stamp, reaction.published_stamp); + const auto pipeline_latency = + calculate_time_diff_ms(pipeline_header_time, reaction.published_stamp); + const auto total_latency = + calculate_time_diff_ms(spawn_cmd_time, reaction.published_stamp); + file << node_latency << " - " << pipeline_latency << " - " << total_latency << ","; + tmp_latency_map[node_name].emplace_back( + std::make_tuple(node_latency, pipeline_latency, total_latency)); + } + } + file << "\n"; + } + } + + // write statistics + + file << "\nStatistics\n"; + file << "Node " + "Name,Min-NL,Max-NL,Mean-NL,Median-NL,Std-Dev-NL,Min-PL,Max-PL,Mean-PL,Median-PL,Std-Dev-" + "PL,Min-TL,Max-TL,Mean-TL,Median-TL,Std-Dev-TL\n"; + for (const auto & [node_name, latency_vec] : tmp_latency_map) { + file << node_name << ","; + + std::vector node_latencies; + std::vector pipeline_latencies; + std::vector total_latencies; + + // Extract latencies + for (const auto & latencies : latency_vec) { + double node_latency, pipeline_latency, total_latency; + std::tie(node_latency, pipeline_latency, total_latency) = latencies; + node_latencies.push_back(node_latency); + pipeline_latencies.push_back(pipeline_latency); + total_latencies.push_back(total_latency); + } + + const auto stats_node_latency = calculate_statistics(node_latencies); + const auto stats_pipeline_latency = calculate_statistics(pipeline_latencies); + const auto stats_total_latency = calculate_statistics(total_latencies); + + file << stats_node_latency.min << "," << stats_node_latency.max << "," + << stats_node_latency.mean << "," << stats_node_latency.median << "," + << stats_node_latency.std_dev << "," << stats_pipeline_latency.min << "," + << stats_pipeline_latency.max << "," << stats_pipeline_latency.mean << "," + << stats_pipeline_latency.median << "," << stats_pipeline_latency.std_dev << "," + << stats_total_latency.min << "," << stats_total_latency.max << "," + << stats_total_latency.mean << "," << stats_total_latency.median << "," + << stats_total_latency.std_dev << "\n"; + } + file.close(); + RCLCPP_INFO(node->get_logger(), "Results written to: %s", ss.str().c_str()); +} +} // namespace reaction_analyzer 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")) 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; }